@osilva These settings have worked in my case:
ros_controllers.yaml
:
# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
joint_model_group: todo_group_name
joint_model_group_pose: todo_state_name
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
loop_hz: 300
cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
joints:
- yumi_robl_joint_1
- yumi_robl_joint_2
- yumi_robl_joint_3
- yumi_robl_joint_4
- yumi_robl_joint_5
- yumi_robl_joint_6
- yumi_robl_joint_7
- yumi_robr_joint_1
- yumi_robr_joint_2
- yumi_robr_joint_3
- yumi_robr_joint_4
- yumi_robr_joint_5
- yumi_robr_joint_6
- yumi_robr_joint_7
sim_control_mode: 1 # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
controller_list:
- name: /yumi/egm/jnt_traj_vel_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
joints:
- yumi_robl_joint_1
- yumi_robl_joint_2
- yumi_robl_joint_3
- yumi_robl_joint_4
- yumi_robl_joint_5
- yumi_robl_joint_6
- yumi_robl_joint_7
- yumi_robr_joint_1
- yumi_robr_joint_2
- yumi_robr_joint_3
- yumi_robr_joint_4
- yumi_robr_joint_5
- yumi_robr_joint_6
- yumi_robr_joint_7
controllers.yaml
:
controller_list:
- name: /yumi/egm/jnt_traj_vel_controller
action_ns: joint_trajectory_action
type: FollowJointTrajectory
joints:
- yumi_robl_joint_1
- yumi_robl_joint_2
- yumi_robl_joint_3
- yumi_robl_joint_4
- yumi_robl_joint_5
- yumi_robl_joint_6
- yumi_robl_joint_7
- yumi_robr_joint_1
- yumi_robr_joint_2
- yumi_robr_joint_3
- yumi_robr_joint_4
- yumi_robr_joint_5
- yumi_robr_joint_6
- yumi_robr_joint_7
ex3_controllers.yaml
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 250
egm_state_controller:
type : abb_egm_state_controller/EGMStateController
publish_rate : 250
jnt_traj_vel_controller:
type: velocity_controllers/JointTrajectoryController
joints:
- yumi_robl_joint_1
- yumi_robl_joint_2
- yumi_robl_joint_3
- yumi_robl_joint_4
- yumi_robl_joint_5
- yumi_robl_joint_6
- yumi_robl_joint_7
- yumi_robr_joint_1
- yumi_robr_joint_2
- yumi_robr_joint_3
- yumi_robr_joint_4
- yumi_robr_joint_5
- yumi_robr_joint_6
- yumi_robr_joint_7
constraints:
stopped_velocity_tolerance: 0
gains:
yumi_robl_joint_1: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_2: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_3: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_4: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_5: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_6: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robl_joint_7: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_1: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_2: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_3: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_4: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_5: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_6: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
yumi_robr_joint_7: {p: 1.0, i: 0, d: 0.00, i_clamp: 0.1}
and changed the default controller in the bringup example launch file to be:
<node pkg="controller_manager" type="spawner" name="stopped" args="--stopped jnt_traj_vel_controller"/>
as it is compatible with MoveIt.
Note that each time you want to execute a motion using MoveIt, you have to start EGM joint:
rosservice call /yumi/rws/sm_addin/start_egm_joint "{}"
, and then switch the controller:
rosservice call /yumi/egm/controller_manager/switch_controller "start_controllers: [jnt_traj_vel_controller]
stop_controllers: ['']
strictness: 1
start_asap: false
timeout: 0.0"
And you should get: ok: True
Finally, here is my moveit_planning_execution.launch
<launch>
<!-- The planning and execution components of MoveIt! configured to run -->
<!-- the "sim" argument controls whether we connect to a Simulated or Real robot -->
<!-- - if sim=false, a robot_ip argument is required -->
<arg name="sim" default="false" doc="Use industrial robot simulator instead of real robot" />
<arg name="robot_ip" unless="$(arg sim)" value="192.168.125.1" doc="IP of controller (only required if not using industrial simulator)" />
<!-- By default, we do not start ...
(more)
Would it be possible to show the frames tree by using:
rosrun tf2_tools view_frames.py
and to save the pdfevince frames.pdf
I took a look at your robot description, looks ok, but before going that rabbit hole, let's check if transforms are working.
@osilva, thanks for your response, here is the frames tree.
Thank you. Yes the gripper fingers are not connected as you can see in frames tree. Let me take a look why.
I think the abb driver sdrf only looks for the standard 14 links (7left, 7 right) as technically you could attach any type of grippers which makes sense: https://github.com/ros-industrial/abb...
But your grippers need to publish as well so I am thinking you need to do this separately by adding to this section in the launch file.
https://github.com/bhomaidan1990/yumi...
@osilva the problem turns to be that the grippers joints were not publishing, remapping
<node name="yumi_joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" > <rosparam param="source_list">["/yumi/rws/joint_states"]</rosparam> </node>
published
0.0
values for the grippers joints, and hence the RobotModel stopped to parse the errors (even though grippers joints positions are0.0
which is not the actual position), but still the MotionPlanning module parsing a warningRequesting initial scene failed
!Partial solution but great progress.
@bhomaidan I will suggest to document your work as an answer. I understand you still have a warning error, but others will benefit from your efforts. Thank you.
@osilva I will try to do it soon with a minimal working example, thanks for your suggestion.