Replies: 2 comments 14 replies
-
I'm going to assume you're using MoveIt with ROS 1, although it doesn't really matter in this case I believe. (having written that: if you are actually using MoveIt 2, please mention that) The MoveIt Setup Assistant (MSA) heavily favours
I would suggest to take a look at an existing MoveIt configuration package in this repository, such as motoman_ma2010_moveit_config. The motoman/motoman_ma2010_moveit_config/config/controllers.yaml Lines 1 to 5 in 63e6242 You will probably have to edit some files to get that file to load though. In the case of the |
Beta Was this translation helpful? Give feedback.
-
First of all I just want to mention that I'm using ROS1. I've changed the Now the `trajectory_execution.launch.xml` looks like this:<launch>
<!-- This file summarizes all settings required for trajectory execution -->
<!-- Define moveit controller manager plugin: fake, simple, or ros_control -->
<arg name="moveit_controller_manager" />
<arg name="fake_execution_type" default="interpolate" />
<!-- Flag indicating whether MoveIt is allowed to load/unload or switch controllers -->
<arg name="moveit_manage_controllers" default="true"/>
<param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
<!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
<param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
<!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
<param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
<!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->
<param name="trajectory_execution/allowed_start_tolerance" value="0.01"/> <!-- default 0.01 -->
<!-- We use pass_all_args=true here to pass fake_execution_type, which is required by fake controllers, but not by real-robot controllers.
As real-robot controller_manager.launch files shouldn't be required to define this argument, we use the trick of passing all args. -->
<include file="$(dirname)/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" pass_all_args="true" />
</launch> Console Output:MoveIt! Launch output:
Trying to Execute a plan and getting Error:
|
Beta Was this translation helpful? Give feedback.
-
I'm trying to create a MoveIt configuration package for the HC10DTP using the MoveIt! Setup assistant.
I'm using https://github.com/EricMarcil/motoman/tree/HC10DTP-Update
For some reason, the setup assistant creates an empty ros_controllers.yaml and for that reason MoveIt! cannot control the real robot.
Any help is appreciated.
The message I'm getting when trying to run the demo.launch file is:
UPDATE:
With the help of @gavanderhoorn I've managed to use the robot through MoveIt.
The solution had two steps:
First Step
We understood there was a problem with MoveIt connecting to the robot's controller (we're using YRC1000micro). The solution here involved altering a few launch files in the launch folder of the moveit config we created using MoveIt Setup Assistant. We created our own moveit_controller_manager and directed trajectory_execution.launch.xml to use it by default.I'll upload the MoveIt config package for this robot.
Second Step
After changing the launch files so the robot responded to MoveIt's motion plan but somewhere in the middle of the execution it stopped for reasons explained below. To solve this we went to the Safety settings in the pendant and change the speed limit (cobot) from 50mm/s to 250mm/s.Beta Was this translation helpful? Give feedback.
All reactions