Open gavanderhoorn opened 3 years ago
Perhaps good to note: the driver supports both joint position and joint velocity interfaces.
Personally, I've noticed some minor vibration when executing trajectories using the position_controllers/JointTrajectoryController
variant of the JTC.
With the EGM session configured for velocity control (ie: set pos_corr_gain
to 0.0
using the set_egm_settings
service), an instance of the velocity_controllers/JointTrajectoryController
could be used, which results in smoother motion.
Unfortunately, as that controller is no longer a pure forwarding controller, it requires gains, and those must be tuned.
@dave992 FYI
For a minimal working example, these are the steps I have taken:
Replace robot_interface_*.launch
with a new launch file based on ex2_rws_and_egm_6axis_robot.launch
joint_names
add an argument to this launch file with the prefix (minus the trailing underscore). Pass this to the robot_nickname
argument of both the abb_rws_state_publisher
and abb_rws_service_provider
nodes. ex2_controllers.yaml
or have the launch file point to your own controllers.yaml
file instead. I've added the following controller definitions to the ex2_controllers.yaml
file, which added both a velocity and position based controller:
joint_velocity_trajectory_controller:
type: velocity_controllers/JointTrajectoryController
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
gains:
joint_1: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_2: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_3: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_4: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_5: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_6: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_position_trajectory_controller: type: position_controllers/JointTrajectoryController joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
- In the second `controller_manager` spawner replace the name `joint_group_velocity_controller` to the name of the controller that you want to use and defined in the previous step. (e.g. `joint_velocity_trajectory_controller` or `joint_position_trajectory_controller` if you use the same added controller definitions as above)
2. Remap one of the available joint state topics (`/rws/joint_states` or `/egm/joint_states`) to `/joint_states`. The EGM version is only actively publishing when an EGM session is active, so here I prefered to use the `/rws/joint_states` as this is available even before an EGM session is active.
3. Update the `controller_list` variable in `*_moveit_config/config/ros_controller.yaml` to point MoveIt to the controller interface it should use:
controller_list:
The `name` parameter is the result of the namespace the controller is launched in by the `controller_manager` spawner (in this case `/egm/`) and the name of the controller you decided to use (e.g. `joint_velocity_trajectory_controller` or `joint_position_trajectory_controller` if you use the same added controller definitions as above)
moveit_planning_execution.launch
as normal. If you used the /rws/joint_states` you should see the robot in the correct pose already. rosservice call /rws/stop_rapid "{}"
rosservice call /rws/pp_to_main "{}"
rosservice call /rws/start_rapid "{}"
rosservice call /rws/sm_addin/start_egm_joint "{}"
controller_list
):
rosservice call /egm/controller_manager/switch_controller "start_controllers: [joint_group_velocity_controller]
stop_controllers: ['']
strictness: 1
start_asap: false
timeout: 0.0"
Personally, I've noticed some minor vibration when executing trajectories using the position_controllers/JointTrajectoryController variant of the JTC.
I did not notice any vibrations when using the position_controllers/JointTrajectoryController
on our IRB4600, but this might be since I was not that close to the robot.
I however did notice that when using the position_controllers/JointTrajectoryController
that I was unable to plan and execute two consecutive motions due to the following error:
[ERROR] Invalid Trajectory: start point deviates from current robot state more than 0.01
I could only execute another motion by manually updating the start state to the current state. Could this have anything to do with the egm setting? (Currently, I did not change any settings)
Swap to the controller MoveIt is using (as defined in the
controller_list
):
if you're going to use MoveIt, I would probably just make sure the JTC gets started as part of the .launch
file you're using to start the driver (instead of the joint_group_velocity_controller
).
[ERROR] Invalid Trajectory: start point deviates from current robot state more than 0.01
I could only execute another motion by manually updating the start state to the current state. Could this have anything to do with the egm setting? (Currently, I did not change any settings)
"the EGM setting"?
That error is from MoveIt, not the driver, so I'm not sure which EGM settings would influence this.
"the EGM setting"?
That error is from MoveIt, not the driver, so I'm not sure which EGM settings would influence this.
Should have been plural ;). To clarify, I do not know if any of the EGM settings have an influence on how well the commanded trajectory is followed and when the robot controller considers the position reached.
The error seems to indicate that the commanded end point is not reached, but does get used as the start point for the follow-up motion.
To clarify, I do not know if any of the EGM settings have an influence on how well the commanded trajectory is followed and when the robot controller considers the position reached.
it's not the robot controller. MoveIt prints this message.
If you don't get a complaint from the Trajectory Execution Manager, then it's likely the trajectory was successfully executed (including the robot reaching its target destination within the requested tolerances).
That would leave MoveIt not having planned from the latest state of the robot, but from some other state.
@dave992 I met the same error showing that Invalid Trajectory: start point deviates from current robot state more than 0.01 and the problem may come from the PID tuning. I at first used your suggested value for the YuMI robot and found the arm was shaking after reaching the goal state. After changing the PID to {p: 1.0, d: 0, i: 0.00, i_clamp: 0.1} I could successfully finish consecutive movements
Thanks for the suggestion, will try this when I pick this up again
Every time i try to use the trajectory controller, I get the following error
[ERROR] [1617093242.897563163]: Could not find parameter robot_description on parameter server
[ERROR] [1617093242.897618266]: Failed to parse URDF contained in 'robot_description' parameter
[ERROR] [1617093242.897651468]: Failed to initialize the controller
[ERROR] [1617093242.897672673]: Initializing controller 'joint_position_trajectory_controller' failed
[ WARN] [1617093243.305342009]: Timed out while waiting for EGM feedback (did the EGM session end on the robot controller?)
[ERROR] [1617093243.899043]: Failed to load joint_position_trajectory_controller
weirdly enough, the group controller work. I am using the robotsudio simulation with the robot IRI1200 0.9 5,
this is the part of the controller.yaml that includes the trajectory controller
joint_velocity_trajectory_controller:
type: velocity_controllers/JointTrajectoryController
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
gains:
joint_1: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_2: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_3: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_4: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_5: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_6: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_position_trajectory_controller:
type: "position_controllers/JointTrajectoryController"
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
I also added the type in the cmake and package files.
The JTC inspects the URDF during load/init to get information on joint
s (here).
Is the robot_description
parameter set and does it contain a valid URDF?
weirdly enough, the group controller work.
that controller does not do anything with URDFs, so it does not need the robot_description
parameter.
Edit: please clarify whether this is a problem related to updating/migrating MoveIt packages. If it isn't, please open a new issue instead of commenting here.
Hi, I am facing similar issue while running abb_irb120_moveit_config (https://github.com/ros-industrial/abb_experimental) for my academic project - if @dave992 could add a tutorial for same or give more clarification on point 2 remapping and on other steps as well it ould be of great help. I want to run rapid files from robotstudio + moveit. Thanks
I am facing similar issue
this is insufficient information to help you.
If you can provide details such as error or warning messages we might be able to provide guidance.
1) I edited (replaced) robot_interface_download_irb120_3_58.launch
<!--
Manipulator specific version of abb_driver's 'robot_interface.launch'.
Defaults provided for IRB 120:
- J23_coupled = false
Usage:
robot_interface_download_irb120.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" doc="IP of the controller" />
<arg name="J23_coupled" default="false" doc="If true, compensate for J2-J3 parallel linkage" />
<rosparam command="load" file="$(find abb_irb120_support)/config/joint_names_irb120_3_58.yaml" />
<include file="$(find abb_driver)/launch/robot_interface.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="J23_coupled" value="$(arg J23_coupled)" />
</include>
</launch>
replaced by code mentioned below although name of file is kept same (robot_interface_download_irb120_3_58.launch)
<?xml version="1.0"?>
<launch>
<arg name="robot_ip" doc="The robot controller's IP address"/>
<!-- Enable DEBUG output for all ABB nodes -->
<arg name="J23_coupled" default="false"/>
<env if="$(arg J23_coupled)" name="ROSCONSOLE_CONFIG_FILE" value="$(find abb_robot_bringup_examples)/config/rosconsole.conf"/>
<!-- ============================================================================================================= -->
<!-- Robot Web Services (RWS) related components. -->
<!-- ============================================================================================================= -->
<!-- RWS state publisher (i.e. general states about the robot controller) -->
<include file="$(find abb_rws_state_publisher)/launch/rws_state_publisher.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
</include>
<!-- RWS service provider (i.a. starting/stopping the robot controller's RAPID execution) -->
<include file="$(find abb_rws_service_provider)/launch/rws_service_provider.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
</include>
<!-- ============================================================================================================= -->
<!-- Externally Guided Motion (EGM) related components. -->
<!-- -->
<!-- Notes: -->
<!-- * This example assumes that a 6-axes robot is used. -->
<!-- * An EGM session must be in running mode before starting 'ros_control' controllers that command motions. -->
<!-- ============================================================================================================= -->
<!-- EGM hardware interface (i.e. 'ros_control'-based interface for interacting with mechanical units) -->
<include file="$(find abb_egm_hardware_interface)/launch/egm_hardware_interface.launch">
<arg name="base_config_file" value="$(find abb_robot_bringup_examples)/config/ex2_hardware_base.yaml"/>
<arg name="egm_config_file" value="$(find abb_robot_bringup_examples)/config/ex2_hardware_egm.yaml"/>
</include>
<!-- Put 'ros_control' components in the "egm" namespace (to match the hardware interface) -->
<group ns="egm">
<!-- Load configurations for 'ros_control' controllers on the parameter server -->
<rosparam file="$(find abb_robot_bringup_examples)/config/ex2_controllers.yaml" command="load"/>
<!-- Two 'ros_control' controller spawners (stopped for the controller that command motions) -->
<node pkg="controller_manager" type="spawner" name="started" args="egm_state_controller joint_state_controller"/>
<node pkg="controller_manager" type="spawner" name="stopped" args="--stopped joint_group_velocity_controller"/>
</group>
</launch>
2) At step two controllers.yaml file having content as -
controller_list:
- name: ""
action_ns: joint_trajectory_action
type: FollowJointTrajectory
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
is replaced by 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
# These settings must match:
# - Joint names extracted from the ABB robot controller.
joint_group_velocity_controller:
type: velocity_controllers/JointGroupVelocityController
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
joint_velocity_trajectory_controller:
type: velocity_controllers/JointTrajectoryController
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
gains:
joint_1: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_2: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_3: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_4: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_5: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_6: {p: 100, i: 1, d: 1, i_clamp: 1}
joint_position_trajectory_controller:
type: position_controllers/JointTrajectoryController
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
3) Don't know how to remap -
4) changed controller-list and ros_controllers.yaml
# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
joint_model_group: irb120_arm
joint_model_group_pose: drop
# 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:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
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: "/egm/joint_position_trajectory_controller"
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
is the updated code.
After this when I launched -
$ roslaunch abb_irb120_moveit_config moveit_planning_execution.launch robot_ip:=192.168.56.01
... logging to /home/nathan/.ros/log/af895fe8-9e25-11eb-bba9-080027cbd5ed/roslaunch-abb-virtualbox-13092.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://abb-virtualbox:42281/
SUMMARY
========
PARAMETERS
* /egm/egm_state_controller/publish_rate: 250
* /egm/egm_state_controller/type: abb_egm_state_con...
* /egm/joint_group_velocity_controller/joints: ['joint_1', 'join...
* /egm/joint_group_velocity_controller/type: velocity_controll...
* /egm/joint_state_controller/publish_rate: 250
* /egm/joint_state_controller/type: joint_state_contr...
* /egm_controller_stopper/no_service_timeout: False
* /egm_controller_stopper/ros_control/controllers/always_ok_to_start: ['egm_state_contr...
* /egm_controller_stopper/ros_control/controllers/ok_to_keep_running: ['egm_state_contr...
* /egm_hardware_interface/egm/channel_1/port_number: 6511
* /egm_hardware_interface/joint_limits/joint_1/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_1/max_velocity: 0.2
* /egm_hardware_interface/joint_limits/joint_2/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_2/max_velocity: 0.2
* /egm_hardware_interface/joint_limits/joint_3/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_3/max_velocity: 0.2
* /egm_hardware_interface/joint_limits/joint_4/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_4/max_velocity: 0.2
* /egm_hardware_interface/joint_limits/joint_5/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_5/max_velocity: 0.2
* /egm_hardware_interface/joint_limits/joint_6/has_velocity_limits: True
* /egm_hardware_interface/joint_limits/joint_6/max_velocity: 0.2
* /egm_hardware_interface/no_service_timeout: False
* /egm_hardware_interface/ros_control/controllers/always_ok_to_start: ['egm_state_contr...
* /egm_hardware_interface/ros_control/controllers/ok_to_keep_running: ['egm_state_contr...
* /rosdistro: melodic
* /rosversion: 1.14.10
* /rws_service_provider/no_connection_timeout: False
* /rws_service_provider/robot_ip: 192.168.56.01
* /rws_service_provider/robot_nickname:
* /rws_service_provider/robot_port: 80
* /rws_state_publisher/no_connection_timeout: False
* /rws_state_publisher/polling_rate: 5
* /rws_state_publisher/robot_ip: 192.168.56.01
* /rws_state_publisher/robot_nickname:
* /rws_state_publisher/robot_port: 80
NODES
/
egm_controller_stopper (abb_egm_hardware_interface/egm_controller_stopper)
egm_hardware_interface (abb_egm_hardware_interface/egm_hardware_interface)
rws_service_provider (abb_rws_service_provider/rws_service_provider)
rws_state_publisher (abb_rws_state_publisher/rws_state_publisher)
/egm/
started (controller_manager/spawner)
stopped (controller_manager/spawner)
auto-starting new master
process[master]: started with pid [13102]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to af895fe8-9e25-11eb-bba9-080027cbd5ed
process[rosout-1]: started with pid [13113]
started core service [/rosout]
process[rws_state_publisher-2]: started with pid [13120]
process[rws_service_provider-3]: started with pid [13121]
process[egm_hardware_interface-4]: started with pid [13122]
process[egm_controller_stopper-5]: started with pid [13127]
process[egm/started-6]: started with pid [13133]
process[egm/stopped-7]: started with pid [13139]
[ WARN] [1618517030.614450986]: Failed to establish RWS connection to the robot controller (attempt 1/5), reason: 'Failed to collect general system info'
[ WARN] [1618517030.618866482]: Failed to establish RWS connection to the robot controller (attempt 1/5), reason: 'Failed to collect general system info'
[ WARN] [1618517031.631449813]: Failed to establish RWS connection to the robot controller (attempt 2/5), reason: 'Failed to collect general system info'
[ WARN] [1618517031.634350292]: Failed to establish RWS connection to the robot controller (attempt 2/5), reason: 'Failed to collect general system info'
[ WARN] [1618517032.662687988]: Failed to establish RWS connection to the robot controller (attempt 3/5), reason: 'Failed to collect general system info'
[ WARN] [1618517032.664341031]: Failed to establish RWS connection to the robot controller (attempt 3/5), reason: 'Failed to collect general system info'
[ WARN] [1618517033.679505746]: Failed to establish RWS connection to the robot controller (attempt 4/5), reason: 'Failed to collect general system info'
[ WARN] [1618517033.684323632]: Failed to establish RWS connection to the robot controller (attempt 4/5), reason: 'Failed to collect general system info'
[ WARN] [1618517034.701735701]: Failed to establish RWS connection to the robot controller (attempt 5/5), reason: 'Failed to collect general system info'
[ WARN] [1618517034.703194946]: Failed to establish RWS connection to the robot controller (attempt 5/5), reason: 'Failed to collect general system info'
[FATAL] [1618517035.708842312]: Runtime error: 'Failed to establish RWS connection to the robot controller'
[FATAL] [1618517035.709619514]: Runtime error: 'Failed to establish RWS connection to the robot controller'
[rws_state_publisher-2] process has died [pid 13120, exit code 1, cmd /home/nathan/abb_moit/devel/lib/abb_rws_state_publisher/rws_state_publisher __name:=rws_state_publisher __log:=/home/nathan/.ros/log/af895fe8-9e25-11eb-bba9-080027cbd5ed/rws_state_publisher-2.log].
log file: /home/nathan/.ros/log/af895fe8-9e25-11eb-bba9-080027cbd5ed/rws_state_publisher-2*.log
[rws_service_provider-3] process has died [pid 13121, exit code 1, cmd /home/nathan/abb_moit/devel/lib/abb_rws_service_provider/rws_service_provider __name:=rws_service_provider __log:=/home/nathan/.ros/log/af895fe8-9e25-11eb-bba9-080027cbd5ed/rws_service_provider-3.log].
log file: /home/nathan/.ros/log/af895fe8-9e25-11eb-bba9-080027cbd5ed/rws_service_provider-3*.log
Please make use of the formatting options that Markdown has available, simply copy-pasting your terminal does not result in great readability as you might have also noticed (link).
Please have a look at the following lines:
[ WARN] [1618517030.614450986]: Failed to establish RWS connection to the robot controller (attempt 1/5), reason: 'Failed to collect general system info'
[FATAL] [1618517035.708842312]: Runtime error: 'Failed to establish RWS connection to the robot controller'
This to me looks like the driver cannot connect to the RWS service of the robot. As this is separate from migrating MoveIt configurations, I would recommend looking through the current issues tracker for comparable issues or start a new one if this is a problem that has not been reported earlier. Quick guess, remove the leading 0
at the end of your IP adress.
The RWS troubleshooting could be helpful to fix RWS communication issues.
@dave992 Hi,I used the abb_robot_driver package to connect to RobotStudio, which I tested without problems. But I sent motion commands using the moveit package as you described above, and the robotic arm in RobotStudio didn't move. No errors were reported throughout the process.
In order to successfully make the robot arm move, I modified the code in three files:ex2_controllers.yaml
、*_moveit_config/config/ros_controller.yaml
andex2_rws_and_egm_6axis_robot.launch
.The test shows that the joint_position_trajectory_controller
starts correctly.
But I don't understand the second point, maybe some configuration is missing?
- Remap one of the available joint state topics (
/rws/joint_states
or/egm/joint_states
) to/joint_states
. The EGM version is only actively publishing when an EGM session is active, so here I prefered to use the/rws/joint_states
as this is available even before an EGM session is active.
@Levelsss Did you get the examples provided by the abb_robot_driver
to work for your robot? That should make sure you can correctly use the driver on its own.
But I don't understand the second point, maybe some configuration is missing?
Remap one of the available joint state topics (/rws/joint_states or /egm/joint_states) to /joint_states. The EGM version is only actively publishing when an EGM session is active, so here I prefered to use the /rws/joint_states as this is available even before an EGM session is active.
RWS and EGM both provide a joint_states
topic, respectively in the /rws
and in the /egm
namespace. You need to remap one of those to /joint_states
as that is where MoveIt by default looks for the topic. It is up to you and your use case which one is best for your application.
@dave992 yes,i get the examples provided by the abb_robot_driver
to work for my robot.I modified the ex2_controllers.yaml
file again , remap /rws/joint_states
to /joint_states
.But when I execute the command in rviz, the robotic arm in robotstudio doesn't move.I hope you can give me some advice on this problem.
Here is my complete ex2_controllers.yaml
file.
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 250
remap:
joint_states: /rws/joint_states
egm_state_controller:
type : abb_egm_state_controller/EGMStateController
publish_rate : 250
# These settings must match:
# - Joint names extracted from the ABB robot controller.
joint_group_velocity_controller:
type: velocity_controllers/JointGroupVelocityController
joints:
- rob1_joint_1
- rob1_joint_2
- rob1_joint_3
- rob1_joint_4
- rob1_joint_5
- rob1_joint_6
- rob2_joint_1
- rob2_joint_2
- rob2_joint_3
- rob2_joint_4
- rob2_joint_5
- rob2_joint_6
joint_position_trajectory_controller:
type: position_controllers/JointTrajectoryController
joints:
- rob1_joint_1
- rob1_joint_2
- rob1_joint_3
- rob1_joint_4
- rob1_joint_5
- rob1_joint_6
- rob2_joint_1
- rob2_joint_2
- rob2_joint_3
- rob2_joint_4
- rob2_joint_5
- rob2_joint_6
gains:
rob1_joint_1:
p: 100
d: 1
i: 1
i_clamp: 1
rob1_joint_2:
p: 100
d: 1
i: 1
i_clamp: 1
rob1_joint_3:
p: 100
d: 1
i: 1
i_clamp: 1
rob1_joint_4:
p: 100
d: 1
i: 1
i_clamp: 1
rob1_joint_5:
p: 100
d: 1
i: 1
i_clamp: 1
rob1_joint_6:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_1:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_2:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_3:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_4:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_5:
p: 100
d: 1
i: 1
i_clamp: 1
rob2_joint_6:
p: 100
d: 1
i: 1
i_clamp: 1
Was recently asked this by a colleague.
At a high-level the changes needed are:
moveit_planning_execution.launch
(or equivalent) to no longerinclude
therobot_interface_download_irb*.launch
from the robot support package, but something similar to (or perhaps even exactly like) abb_robot_bringup_examples/launch/ex2_rws_and_egm_6axis_robot.launch. This is responsible for loading theros_control
controller configuration onto the parameter server and starting the required nodes (main driver and RWS service node)name
and/oraction_ns
key in thecontrollers.yaml
file in the MoveIt configuration pkg (or equivalent file which configures thecontroller_list
parameter) to use the Action server topic of the new driver. In ROS-Industrial distributed MoveIt cfg pkgs, these are typically set to""
(forname
) andjoint_trajectory_action
foraction_ns
.ros_control
configuration from the bringup examples pkg in this repository, users would also need to add stanzas to add aJointTrajectoryController
to the configuration. MoveIt cannot talk to theJointGroupVelocityController
loaded by default.Of course, contrary to the old driver,
abb_robot_driver
needs some more management, so before trajectories can be executed, users will have to use the appropriate ROS services offered by the RWS service node to put the ABB controller in the right state (ie: make it run the required RAPID programs).The sequence of service invocations is shown in the readme of the
abb_robot_bringup_examples
package.