![]() |
Sinai_Aranda
May 2 |
Hi,
I’m working with Ros indigo and motoman’s robot SDA20D dx100 controller. MotoRosdx100.out is correctly installed. I run roslaunch robot_multigroup_interface_streaming_dx100 + robot_ip and it shows a problem: “Message callback for message type: 2017, not executed”, in rostopic echo /joint_states it shows:
header: --------------------->this is about left arm
seq: 14196
stamp:
secs: 1525125567
nsecs: 507619542
frame_id: ‘’
name: [‘joint_s’, ‘joint_l’, ‘joint_u’, ‘joint_r’, ‘joint_b’, ‘joint_t’]
position: [0.09135707467794418, 0.3661271333694458, 0.0, 0.0, 0.0, 1.5187928511295468e-05]
velocity: []
effort: []
header: --------------------->this is about right arm
seq: 14197
stamp:
secs: 1525125567
nsecs: 508185940
frame_id: ‘’
name: [‘joint_s’, ‘joint_l’, ‘joint_u’, ‘joint_r’, ‘joint_b’, ‘joint_t’]
position: [0.0, 0.0, 0.0, 0.0, 1.5187928511295468e-05, -1.5187928511295468e-05]
velocity: []
effort: []
header: --------------------->this is about torso
seq: 14198
stamp:
secs: 1525125567
nsecs: 508618419
frame_id: ‘’
name: [‘joint_s’, ‘joint_l’, ‘joint_u’, ‘joint_r’, ‘joint_b’, ‘joint_t’]
position: [-0.00521701667457819, 0.0, 0.0, 0.0, 0.0, 0.0]
velocity: []
effort: []
Does anyone know how to make the correct configuration?
Visit Topic or reply to this email to respond.
To unsubscribe from these emails, click here.
![]() |
gavanderhoorn
May 2 |
I’m not entirely sure, but I believe you’re not running the multi-group version of the driver.
Message 2017
is ROS_MSG_MOTO_JOINT_FEEDBACK_EX
(from REP-I0004), which is the message used by the driver to report multi-group joint states. Unless the multi-group codepaths are used in motoman_driver
, the ROS nodes will not know how to deserialise those messages and the multi-group interface will not work.
Can you please provide some more details on what exactly you are launching, where you got it from, and what parameters you are providing it (ie: packages, launch files, yaml configuration files, etc).
IIRC, the group for the torso should not have all those joints.
![]() |
Sinai_Aranda
May 3 |
after,
rosparam load /motoman_sda20d/urdf/motoman_sda20d.urdf robot_description
rosparam set controller_joint_names “[arm_left_joint_1_s, arm_left_joint_2_l, arm_left_joint_3_e, arm_left_joint_4_u, arm_left_joint_5_r, arm_left_joint_6_b, arm_left_joint_7_t, arm_right_joint_1_s, arm_right_joint_2_l, arm_right_joint_3_e, arm_right_joint_4_u, arm_right_joint_5_r, arm_right_joint_6_b, arm_right_joint_7_t, torso_joint_b1]”
How can I do the correct configuration?
gavanderhoorn
May 4 |
Did you have a reason for deleting your two posts?
![]() |
gavanderhoorn
May 4 |
@Sinai_Aranda: perhaps you can use Danfoa/invite-robotics as inspiration. It is for an SDA10, but that should be almost a search->replace action at this level.
The invite_motoman_support
pkg shows you how to configure the controller_joint_names
and the other required parameters.
Note that the pkgs in Danfoa/invite-robotics
contain a lot of other things (for integration of a gripper fi) that you can ignore. Also note that they are essentially a customised version of the pkgs in ros-industrial/motoman
and ros-industrial/motoman_experimental
.
![]() |
Sinai_Aranda
May 7 |
hi, I have the new configuration for package, now I can see the joint states correct of right arm, left arm and torso. But only run one time, and it’s show this:
started roslaunch server http://sda20-Aspire-S3:33061/
SUMMARY
PARAMETERS
NODES
/
joint_state (motoman_driver/robot_state)
joint_trajectory_action (motoman_driver/motoman_driver_joint_trajectory_action)
motion_streaming_interface (motoman_driver/motion_streaming_interface)
auto-starting new master
process[master]: started with pid [7205]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to c9baf556-51fd-11e8-8a16-009a9e9d9347
process[rosout-1]: started with pid [7218]
started core service [/rosout]
process[joint_state-2]: started with pid [7228]
process[motion_streaming_interface-3]: started with pid [7236]
process[joint_trajectory_action-4]: started with pid [7243]
[FATAL] [1525701109.760904112]: ASSERTION FAILED
** file = /home/sda20/cidesi_robots_ws/src/motoman-indigo-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp**
** line = 320**
** cond = all_joint_state.positions.size() == all_joint_names.size()**
[joint_state-2] process has died [pid 7228, exit code -5, cmd /home/sda20/cidesi_robots_ws/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/sda20/.ros/log/c9baf556-51fd-11e8-8a16-009a9e9d9347/joint_state-2.log].
log file: /home/sda20/.ros/log/c9baf556-51fd-11e8-8a16-009a9e9d9347/joint_state-2.log*
Will it be from the motoplus or this configuration?
gavanderhoorn
May 8 |
Can you show us the value of the controller_joint_names
parameter?
And could you please post the output of roslaunch
when you start it with the --screen
command line option?
![]() |
Sinai_Aranda
May 8 |
roslaunch motoman_sda20d_moveit_config robot_interface_streaming_sda20d.launch --screen… logging to /home/sda20/.ros/log/55952d18-52d4-11e8-93b2-009a9e9d9347/roslaunch-sda20-Aspire-S3-15122.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://sda20-Aspire-S3:43152/
SUMMARY
PARAMETERS
NODES
/
joint_state (motoman_driver/robot_state)
joint_trajectory_action (motoman_driver/motoman_driver_joint_trajectory_action)
motion_streaming_interface (motoman_driver/motion_streaming_interface)
ROS_MASTER_URI=http://localhost:11311
core service [/rosout] found
process[joint_state-1]: started with pid [15140]
process[motion_streaming_interface-2]: started with pid [15141]
[ INFO] [1525793277.774871649]: Added message handler for message type: 0
process[joint_trajectory_action-3]: started with pid [15150]
[ INFO] [1525793277.783318367]: Robot state connecting to IP address: ‘192.168.255.10:50241’
[ INFO] [1525793277.786943671]: Loading topic list
[ INFO] [1525793277.787028643]: Found 4 topics
[ INFO] [1525793277.787093476]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.787155804]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.787214808]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.787274280]: Topic(state_value): [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.787322502]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.787537892]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.787624508]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.787683830]: Loading group: [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.787750856]: Loaded 4 groups
[ INFO] [1525793277.787833872]: Initializing robot state 4 groups
[ INFO] [1525793277.787894632]: Initializing message manager with default comms fault handler
[ INFO] [1525793277.787941047]: Default communications fault handler successfully initialized
[ INFO] [1525793277.787979140]: Initializing message manager
[ INFO] [1525793277.788027577]: Added message handler for message type: 1
[ INFO] [1525793277.809585729]: Added message handler for message type: 10
[ INFO] [1525793277.810346040]: Joint Trajectory Interface connecting to IP address: ‘192.168.255.10:50240’
[ INFO] [1525793277.813892230]: Added message handler for message type: 15
[ INFO] [1525793277.813995011]: Creating joint_feedback_ex_relay_handler with 4 groups
[ INFO] [1525793277.819683274]: Loading topic list
[ INFO] [1525793277.819847125]: Found 4 topics
[ INFO] [1525793277.819924352]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.819994004]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.820046525]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.820089922]: Topic(state_value): [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.820134699]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.820247098]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.820320855]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.820388747]: Loading group: [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.820461235]: Loaded 4 groups
[ INFO] [1525793277.820530037]: MotomanJointTrajectoryStreamer: init
[ INFO] [1525793277.820582817]: JointTrajectoryStreamer: init
[ INFO] [1525793277.821819561]: Connected to server
[ INFO] [1525793277.829682953]: Loading topic list
[ INFO] [1525793277.829783638]: Found 4 topics
[ INFO] [1525793277.829828822]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.829886254]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.829948569]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.830012649]: Topic(state_value): [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.830065815]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525793277.830190502]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525793277.830258075]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525793277.830316122]: Loading group: [group:3,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525793277.830378247]: Loaded 4 groups
[ INFO] [1525793277.830492358]: Added message handler for message type: 2017
[ INFO] [1525793277.833911412]: Connected to server
[ INFO] [1525793277.833981932]: Successfully initialized robot state interface
[ INFO] [1525793277.834048878]: Entering message manager spin loop
[ INFO] [1525793277.939026704]: Unlocking mutex
[ INFO] [1525793277.939193526]: Starting Motoman joint trajectory streamer thread
[ INFO] [1525793277.944351291]: Connecting to robot motion server
[ WARN] [1525793277.944421356]: Tried to connect when socket already in connected state
[FATAL] [1525793278.015168488]: ASSERTION FAILED
file = /home/sda20/cidesi_robots_ws/src/motoman-indigo-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
line = 320
cond = all_joint_state.positions.size() == all_joint_names.size()
[joint_state-1] process has died [pid 15140, exit code -5, cmd /home/sda20/cidesi_robots_ws/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/sda20/.ros/log/55952d18-52d4-11e8-93b2-009a9e9d9347/joint_state-1.log].
log file: /home/sda20/.ros/log/55952d18-52d4-11e8-93b2-009a9e9d9347/joint_state-1*.log
In new terminals (these just it’s show before of the error):
rostopic echo /sda20d/sda20d_r1_controller/joint_states
header:
seq: 0
stamp:
secs: 1525791870
nsecs: 125187133
frame_id: ‘’
name: [‘arm_left_joint_1_s’, ‘arm_left_joint_2_l’, ‘arm_left_joint_3_e’, ‘arm_left_joint_4_u’, ‘arm_left_joint_5_r’, ‘arm_left_joint_6_b’, ‘arm_left_joint_7_t’]
position: [-0.32970359921455383, 0.983213484287262, -0.030645526945590973, -1.0131772756576538, -1.3398334980010986, -1.8006503582000732, 1.0624170303344727]
velocity: []
effort: []
rostopic echo /sda20d/sda20d_r2_controller/joint_states
header:
seq: 0
stamp:
secs: 1525791870
nsecs: 123301906
frame_id: ‘’
name: [‘arm_right_joint_1_s’, ‘arm_right_joint_2_l’, ‘arm_right_joint_3_e’, ‘arm_right_joint_4_u’, ‘arm_right_joint_5_r’, ‘arm_right_joint_6_b’, ‘arm_right_joint_7_t’]
position: [-0.08535750955343246, 1.1426793336868286, 0.18094155192375183, -1.0275626182556152, -0.9328728914260864, -1.4836479425430298, 0.06319399178028107]
velocity: []
effort: []
rostopic echo /sda20d/sda20d_b1_controller/joint_states
header:
seq: 0
stamp:
secs: 1525791870
nsecs: 125437761
frame_id: ‘’
name: [‘torso_joint_b1’]
position: [0.06071678176522255]
velocity: []
effort: []
rostopic echo /sda20d/sda20d_b2_controller/joint_states
In display of the robot Motoplus:
Controller number of group = 3
StateServer Send failure. Closing state server connection.
Closing Motion Server Connection.
Motion Server Connection Closed.
Exist a problem with motoman_driver related with driver: assertion in joint_relay_handler when controller has < 4 motion groups configured and Removed version0 parameters (as much as possible)?
I used the last motoman_driver version for indigo-devel.
![]() |
gavanderhoorn
May 8 |
I’m wondering whether there is some misconfiguration / misunderstanding here.
@ted-miller: afaik, all SDAx robots have 4 groups, with groups 2 & 3 controlling the two torso joints, correct? How is this configured on the DX100?
In the screenshot provided by @Sinai_Aranda, it looks like only 3 AddToIncQueue
tasks are created. This strikes me as odd.
Edit: @Sinai_Aranda: could you test with group nr 3 (so the fourth entry) removed from your sda20d_motion_interface.yaml
A wireshark capture of some traffic would also help.
![]() |
andreaskoepf
May 8 |
@gavanderhoorn I can confirm that a SDA can be operated with three groups on a DX100. Removing the shared torso axis was the only way we found to execute full body motions (both arms + torso) with a DX100. Primary reason for this is the Motoplus driver which has to split the updates for both robots (R1, R2) on the DX100 into two different calls, e.g. see MotionServer.c#L1693-L1715. If both calls are executed after each other the DX100 complains about different joint values for the shared base axis (even when you try to set the exact same values).
andreaskoepf
May 8 |
Just one important thing regarding motoman/#91 (>1 but <4 groups): see my quickfix here.
![]() |
ted-miller
May 8 |
@gavanderhoorn The SDA operates differently on a DX100 than an FS100 or above.
The DX100 version of MotoROS can only support 2 control groups. This is a limitation of the API which controls motion (mpMeiIncrementMove). So, for an SDA robot, you cannot control both arms and also the torso.
I just realized that the max-group-detection mechanism in MotoROS doesn’t have the restriction for DX100. I have just updated PR #213 to include this detection. In this new version, it will not create a task for the third group.
I’m confused by @andreaskoepf’s comment. Are you saying you were able to control all three groups with MotoROS on a DX100?
![]() |
gavanderhoorn
May 8 |
@ted-miller: ok, this makes sense for me again now.
So how are the motion groups configured then for the SDA on DX100?
We should document this on the wiki.
@andreaskoepf: do I understand you correctly that you configured things such that you can only control both arms, but not the torso also on DX100?
![]() |
andreaskoepf
May 8 |
@ted-miller I did this some time ago. I also had to tweak the Motoplus driver a bit to make this work, especially in MotionServer.c I added this:
// first robot
moveData.ctrl_grp = 1 | (1 << 2); // AKo: Hard coded special value for our SD10D R1+B1 R2 special configuration
ret = mpMeiIncrementMove(MP_SL_ID1, &moveData);
But yes, with these changes it is definitely possible to operate all 15 joints of the SDA10D with a DX100 controller simultaneously (run whole body motions).
We at Xamla added a couple of more things to the Motoplus driver for better realtime control etc, e.g. see FT control or joystick control. In general an issue of the DX100 is the big latency of the system (~ 100ms) which is probably caused by lower level moving average filtering in the motor controllers.
![]() |
Sinai_Aranda
May 8 |
@andreaskoepf This can apply on indigo-devel (here)? The difference it’s that the first take i=MOT_MAX_GR -1 it’s decreasing. The other from zero to until number groups.
@gavanderhoorn I have eliminated group three and two for arms, but I have the same problem:
[ INFO] [1525802331.438267018]: Added message handler for message type: 0
[ INFO] [1525802331.443545844]: Robot state connecting to IP address: ‘192.168.255.10:50241’
[ INFO] [1525802331.447706704]: Loading topic list
[ INFO] [1525802331.447797778]: Found 4 topics
[ INFO] [1525802331.447990373]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.448174949]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.448349955]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.448586850]: Topic(state_value): [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.448777123]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.449097947]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.449303266]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.449477517]: Loading group: [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.449663703]: Loaded 3 groups
[ INFO] [1525802331.449878726]: Initializing robot state 3 groups
[ INFO] [1525802331.450044933]: Initializing message manager with default comms fault handler
[ INFO] [1525802331.450200052]: Default communications fault handler successfully initialized
[ INFO] [1525802331.450351758]: Initializing message manager
[ INFO] [1525802331.450507301]: Added message handler for message type: 1
[ INFO] [1525802331.452929789]: Joint Trajectory Interface connecting to IP address: ‘192.168.255.10:50240’
[ INFO] [1525802331.457070987]: Loading topic list
[ INFO] [1525802331.457150840]: Found 4 topics
[ INFO] [1525802331.457232638]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.457297440]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.457354225]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.457413602]: Topic(state_value): [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.457467015]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.457594219]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.457662366]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.457722454]: Loading group: [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.457795325]: Loaded 3 groups
[ INFO] [1525802331.457857552]: MotomanJointTrajectoryStreamer: init
[ INFO] [1525802331.457904468]: JointTrajectoryStreamer: init
[ INFO] [1525802331.458500373]: Connected to server
[ WARN] [1525802331.459938562]: Unable to read velocity limits from ‘robot_description’ param. Velocity validation disabled.
[ INFO] [1525802331.469278550]: Added message handler for message type: 10
[ INFO] [1525802331.471845604]: Added message handler for message type: 15
[ INFO] [1525802331.471925152]: Creating joint_feedback_ex_relay_handler with 3 groups
[ INFO] [1525802331.479876680]: Loading topic list
[ INFO] [1525802331.479983408]: Found 4 topics
[ INFO] [1525802331.480034636]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.480086592]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.480130836]: Topic(state_value): [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.480174577]: Topic(state_value): [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.480214888]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525802331.480327181]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525802331.480380941]: Loading group: [group:2,joints:{torso_joint_b1},name:sda20d_b1_controller,ns:sda20d]
[ INFO] [1525802331.480426611]: Loading group: [group:2,joints:{torso_joint_b2},name:sda20d_b2_controller,ns:sda20d]
[ INFO] [1525802331.480475311]: Loaded 3 groups
[ INFO] [1525802331.481578268]: Added message handler for message type: 2017
[ INFO] [1525802331.485001516]: Connected to server
[ INFO] [1525802331.485061847]: Successfully initialized robot state interface
[ INFO] [1525802331.485108232]: Entering message manager spin loop
[ INFO] [1525802331.552928670]: Unlocking mutex
[ INFO] [1525802331.553042195]: Starting Motoman joint trajectory streamer thread
[ INFO] [1525802331.558210887]: Connecting to robot motion server
[ WARN] [1525802331.558278139]: Tried to connect when socket already in connected state
[FATAL] [1525802331.673627559]: ASSERTION FAILED
file = /home/sda20/cidesi_robots_ws/src/motoman-indigo-devel/motoman_driver/src/industrial_robot_client/joint_relay_handler.cpp
line = 320
cond = all_joint_state.positions.size() == all_joint_names.size()
[joint_state-1] process has died [pid 23590, exit code -5, cmd /home/sda20/cidesi_robots_ws/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/sda20/.ros/log/00b5a52a-52e8-11e8-97d3-009a9e9d9347/joint_state-1.log].
log file: /home/sda20/.ros/log/00b5a52a-52e8-11e8-97d3-009a9e9d9347/joint_state-1*.log
[ INFO] [1525807605.449170847]: Added message handler for message type: 0
[ INFO] [1525807605.455824568]: Robot state connecting to IP address: ‘192.168.255.10:50241’
[ INFO] [1525807605.458944544]: Loading topic list
[ INFO] [1525807605.459047732]: Found 2 topics
[ INFO] [1525807605.459115870]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.459233539]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.459333939]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.459564509]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.459692435]: Loaded 2 groups
[ INFO] [1525807605.459811539]: Initializing robot state 2 groups
[ INFO] [1525807605.459909898]: Initializing message manager with default comms fault handler
[ INFO] [1525807605.459998111]: Default communications fault handler successfully initialized
[ INFO] [1525807605.460075912]: Initializing message manager
[ INFO] [1525807605.460160439]: Added message handler for message type: 1
process[joint_trajectory_action-3]: started with pid [25755]
[ INFO] [1525807605.470761572]: Added message handler for message type: 10
[ INFO] [1525807605.472210634]: Added message handler for message type: 15
[ INFO] [1525807605.472312112]: Creating joint_feedback_ex_relay_handler with 2 groups
[ INFO] [1525807605.482048725]: Added message handler for message type: 2017
[ INFO] [1525807605.482837964]: Joint Trajectory Interface connecting to IP address: ‘192.168.255.10:50240’
[ INFO] [1525807605.485417537]: Connected to server
[ INFO] [1525807605.485497443]: Successfully initialized robot state interface
[ INFO] [1525807605.485588419]: Entering message manager spin loop
[ INFO] [1525807605.490193465]: Loading topic list
[ INFO] [1525807605.490264995]: Found 2 topics
[ INFO] [1525807605.490309897]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.490350038]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.490412647]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.490550847]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.490629770]: Loaded 2 groups
[ INFO] [1525807605.490700324]: MotomanJointTrajectoryStreamer: init
[ INFO] [1525807605.490748014]: JointTrajectoryStreamer: init
[ INFO] [1525807605.491187031]: Connected to server
[ INFO] [1525807605.500241632]: Loading topic list
[ INFO] [1525807605.500364735]: Found 2 topics
[ INFO] [1525807605.500438567]: Topic(state_value): [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.500509860]: Topic(state_value): [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.500577576]: Loading group: [group:0,joints:{arm_right_joint_1_s,arm_right_joint_2_l,arm_right_joint_3_e,arm_right_joint_4_u,arm_right_joint_5_r,arm_right_joint_6_b,arm_right_joint_7_t},name:sda20d_r2_controller,ns:sda20d]
[ INFO] [1525807605.500706123]: Loading group: [group:1,joints:{arm_left_joint_1_s,arm_left_joint_2_l,arm_left_joint_3_e,arm_left_joint_4_u,arm_left_joint_5_r,arm_left_joint_6_b,arm_left_joint_7_t},name:sda20d_r1_controller,ns:sda20d]
[ INFO] [1525807605.500785825]: Loaded 2 groups
[ INFO] [1525807605.561350326]: Unlocking mutex
[ INFO] [1525807605.561490191]: Starting Motoman joint trajectory streamer thread
[ INFO] [1525807605.566693825]: Connecting to robot motion server
[ WARN] [1525807605.566751532]: Tried to connect when socket already in connected state
[FATAL] [1525807605.575907532]: ASSERTION FAILED
file = /opt/ros/indigo/include/ros/publisher.h
line = 102
cond = false
message =
[FATAL] [1525807605.575987132]: Call to publish() on an invalid Publisher
[FATAL] [1525807605.576013285]:
[joint_state-1] process has died [pid 25742, exit code -5, cmd /home/sda20/cidesi_robots_ws/devel/lib/motoman_driver/robot_state __name:=joint_state __log:=/home/sda20/.ros/log/00b5a52a-52e8-11e8-97d3-009a9e9d9347/joint_state-1.log].
log file: /home/sda20/.ros/log/00b5a52a-52e8-11e8-97d3-009a9e9d9347/joint_state-1*.log
andreaskoepf
May 8 |
@Sinai_Aranda (and all) If you like you could try our pre-release version of Rosvita which is a ready-to-use ROS docker container with web UI (see our early access documentation). It comes with models & configurations for SDA10D/F, Universal Robots and Meca500 and is for free for public research institutes and private users. Just send me a PM.
Sinai_Aranda
May 8 |
I have resolved the problem. The count is from zero for number of groups just delete ros_assert. This have a while.
In rostopic now already it’s show me all joints in time real. Also, I move the robot (R1, R2, B1) and it’s change the joint values. This load yaml of 4 groups (same file), but do not show values of B2 joint.
So, I will start to do test of moving robot. thanks!!!
![]() |
andreaskoepf
May 8 |
gavanderhoorn:
@andreaskoepf: do I understand you correctly that you configured things such that you can only control both arms, but not the torso also on DX100?
No, we have no limitation of moving the torso of our SDA10D with DX100, e.g. we can move all 15 joints, 7 joints of one arm, 14 joints of two arms, or 8 joints of one arm and torso etc. We are using a slightly modified version of the MotoPlus driver and the Motoman ROS backend (e.g. correcting the deserialization of the joint_feedback_ex message, which also other did with some more lines of code as in Two arms and rail with DX100 PR.
Probably the hardest change we had to make: In the robot controller configuration we removed the B2 group.
These are the sda10d_motion_interface.yaml and the joint_names_sda10d.yaml we are using for our DX100.
And regarding the MotoPlus driver (@ted-miller): The documentation of mpMeiIncrementMove
was quite challenging to decode - I guess the text about MP_POS_DATA.ctrl_grp
in the mpManualMOV
description also applies to mpMeiIncrementMove
. So what I found is: It is possible to control R1 + B1 in one mpMeiIncrementMove
command for MP_SL_ID1
by setting the corresponding two bits of the ctrl_grp
member. After that it is possible to execute another mpMeiIncrementMove
for MP_SL_ID2
with the ctrl_grp
mask with a bit set for the data for R2
. Both calls being made in one interpolation period results in smooth whole body motions.
![]() |
gavanderhoorn
May 9 |
Sinai_Aranda:
I have resolved the problem. The count is from zero for number of groups just delete ros_assert.
That is not a solution. The assert is there for a reason, and you’re essentially running into motoman/#91.
Looking at the output in [your previous post[(Using the Motoman SDA20D Dual-arms DX100 ROS Interface(Indigo)), it appears you’ve duplicated group 2
, that won’t work. Your robot has either 2 or 3 groups, and the motion_interface.yaml
should reflect that.
The configuration that @andreaskoepf posted would be more like what you should be using, but then we’d have to fix motoman/#91.
If @ted-miller could clarify whether the approach used by @andreaskoepf is acceptable / supported, you could even use that configuration and the MotoPlus changes. But let’s wait for his comments.
![]() |
gavanderhoorn
May 9 |
Thanks for the clarification.
If @ted-miller vets your ‘trick’, it’d be nice if we could get that into MotoROS. You’re not the only ones using DX100 controllers with SDA robots, so it’d be nice if we could support that properly.
andreaskoepf:
we have no limitation of moving the torso of our SDA10D with DX100, e.g. we can move all 15 joints, 7 joints of one arm, 14 joints of two arms, or 8 joints of one arm and torso etc
So just for my own understanding: which group on your controller now controls the b1
joint? I was under the impression that the DX100 supported up to 2 groups, but you seem to have 3. Or is the ‘limitation’ in mpMeiIncrementMove(..)
?
andreaskoepf:
We are using a slightly modified version of the MotoPlus driver and the Motoman ROS backend (e.g. correcting the deserialization of the joint_feedback_ex message, which also other did with some more lines of code as in Two arms and rail with DX100 PR.
Yes, we need to get those changes (there are more) merged into motoman_driver
. They’ve been sitting in a fork for too long.
Would you be willing to test some candidate fixes on your SDA?
![]() |
gavanderhoorn
May 9 |
The jogging interface looks really nice @andreaskoepf.
If the changes are compatible with the other functionality of MotoROS/motoman_driver
, it would be great if we could integrate that ‘upstream’. Would you be willing/interested in that?
I haven’t checked your fork yet, but is this similar to ros-industrial/motoman#37?
![]() |
andreaskoepf
May 9 |
@gavanderhoorn Unfortunately our fork is not really in ‘shape’ for easily creating a PR. There are a couple of things that would have to be cleaned and squashed as a lot of debug stuff was checked in which we used to understand what was going on. Our MotoPlus driver changes have not yet been published … e.g. we added a trapezoidal velocity profile controller to the MotoPlus driver which directly moves to streamed set-points without taking a detour over the trajectory spline-interpolation.
(Rosvita has a custom jogging node which allows to jog by twist, catesian-setpoint or joint-directions with safe timeout handling (e.g. to be used via unreliable web-interface) with checking for collision and gracefully handling singularities etc. With the Rosvita UI you can simply enable jogging mode, drag the 3D Cursor at the endeffector and the robot follows.)
![]() |
gavanderhoorn
May 9 |
I’m not necessarily looking for a quick fix/easy grab, but would be interested in getting the changes you describe merged in the main distribution. That way we advance the state-of-the-art and avoid fragmented development, which I believe is very valuable.
If that is something you can agree with, perhaps we can find some way to work towards those goals.
One possibility I see could be for Xamla to apply for a ROSIN FTP. That way you could be (among other things) financially supported to work on the driver.
If that would be of interest, contact me off-list and I can provide you with more information.
![]() |
ted-miller
May 9 |
@andreaskoepf Assuming you still have access to your SDA10D, could you please email me a copy of ALL.PRM and SYSTEM.SYS files. (Please rename the SYSTEM.SYS to SYSTEM.TXT to get past email filters.) There are parameters that control which groups are mapped to the SL-ID slots. I am interested to see how your robot is configured. I don’t have a DX SDA to experiment with right now.
To save the files from the teach pendant:
[Ext Memory] > [Device] > Select CF or USB.
[Ext Memory] > [Save] > “Parameter” > “Batch Parameter”.
[Ext Memory] > [Save] > “System Data” > “System Information”.
![]() |
andreaskoepf
May 10 |
gavanderhoorn:
Would you be willing to test some candidate fixes on your SDA?
We are absolutely interested in collaborating regarding the Motoman ROS driver. Due to the natural situation that most ros-industrial developers only get in touch with a very limited number of systems we see this as crucial.
ted-miller:
could you please email me a copy of ALL.PRM and SYSTEM.SYS files. (Please rename the SYSTEM.SYS to SYSTEM.TXT
Sure, we have sent the files. btw I have pasted the start-up output of the MotoROS driver on our system in a comment to the MotoROS v.1.8.0 PR.
gavanderhoorn
May 16 |
The PR for v1.8.0
now contains code that should be close to what you are doing with the two/three motion groups @andreaskoepf.
![]() |
Sinai_Aranda
May 28 |
Hi, I load motoros 1.8v of @ted-miller, I have executed roslaunch successfully. But now have other problem when launch demo (without joint state publisher) with the arm left, already that the joints is missing.
[ERROR] [1527541542.427483218]: State monitor received invalid joint state (number of joint names does not match number of positions)
[ERROR] [1527541542.559572523]: Robot state publisher received an invalid joint state vector
[ERROR] [1527541542.652458005]: Robot state publisher received an invalid joint state vector
[ WARN] [1527541542.682741048]: The complete state of the robot is not yet known. Missing arm_left_joint_1_s, arm_left_joint_2_l, arm_left_joint_3_e, arm_left_joint_4_u, arm_left_joint_5_r, arm_left_joint_6_b, arm_left_joint_7_t
On rostopic echo /sda20d/sda20d_r1_controller/joint_states yes they are:
header:
seq: 54746
stamp:
secs: 1527541767
nsecs: 419976021
frame_id: ‘’
name: [‘arm_left_joint_1_s’, ‘arm_left_joint_2_l’, ‘arm_left_joint_3_e’, ‘arm_left_joint_4_u’, ‘arm_left_joint_5_r’, ‘arm_left_joint_6_b’, ‘arm_left_joint_7_t’]
position: [-0.24274393916130066, 0.8650458455085754, 0.09747595340013504, -0.3556790053844452, -0.25175508856773376, -0.11210209876298904, -0.2976524233818054]
velocity: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
effort: []
But difference on rostopic echo /joint_states the position is empty:
header:
seq: 178122
stamp:
secs: 1527541902
nsecs: 769456976
frame_id: ‘’
name: [‘arm_left_joint_1_s’, ‘arm_left_joint_2_l’, ‘arm_left_joint_3_e’, ‘arm_left_joint_4_u’, ‘arm_left_joint_5_r’, ‘arm_left_joint_6_b’, ‘arm_left_joint_7_t’]
position: []
velocity: []
effort: []
![]() |
ted-miller
May 30 |
Hello Sinai,
Can you please try three things:
Make sure there is only one instance of MotoROS installed on your controller. Boot into Maintenance mode. Touch [MotoPlus Apl] > [File List]. Make sure there is only one .out file loaded.
Please take a picture of the VGA monitor connected to the robot. I would like to see the startup initialization messages.
Please run a wireshark capture on the ROS PC. This will record the network communication between the robot and PC. https://jlospinoso.github.io/software/wireshark/networks/ubuntu/2015/02/11/configuring-wireshark-on-ubuntu-14.html
![]() |
Sinai_Aranda
May 30 |
Hi @ted-miller, I changed the init_ros job:
/JOB
//NAME INIT_ROS
//POS
///NPOS 0,0,0,0,0,0
//INST
///DATE 2018/05/30 10:54
///ATTR SC,RW
NOP
PSTART JOB:ROS_R1 SUB1
PSTART JOB:ROS_R2 SUB2
PSTART JOB:ROS_S1 SUB3
PWAIT SUB1
END
This is the wireshark print.
![]() |
ted-miller
May 30 |
The monitor output looks good.
For the wireshark capture, can you please zip the pcapng file and attach it? I am unable to filter and read the raw printed data.
For the INIT_ROS job, I added special jobs for DX100 SDA in my latest commit. https://github.com/ros-industrial/motoman/pull/213/commits/df1256dc6dfd17e518f396cc7aba0517c44c8a62 Please use the jobs in the folder “two_arms_with_base”.
Based on your post, I am assuming that your waist axis is configured as a “station” instead of a “base”. I don’t know if this will work or not. My testing was done using a base-axis. You may need to reconfigure that axis. If you need help with that, please contact Yaskawa Motoman Tech Support and they can provide detailed instructions for your robot.
@gavanderhoorn, do you have any advice about the latest error? Assuming that the robot is indeed reporting the joint states, then I’m not sure what the ROS error messages mean.
gavanderhoorn
May 31 |
I first want to see the wireshark capture before looking into this more.
![]() |
Sinai_Aranda
June 4 |
Hi, I configured the waist axis to “base” and I loaded the jobs to robot. The problem persists, this is the wireshark file. Also, I try to monitoring the joint states of real robot in rviz (demo.launch) but now just R2 is correct.
[ INFO] [1528141714.315548270]: all_joint_state.positions: 0 == all_joint_names: 7
[ INFO] [1528141714.315751159]: all_joint_state.positions: 1 == all_joint_names: 1
[ INFO] [1528141714.315910410]: all_joint_state.positions: 7 == all_joint_names: 7
[ERROR] [1528141487.782130639]: State monitor received invalid joint state (number of joint names does not match number of positions)
[ERROR] [1528141487.813911850]: Robot state publisher received an invalid joint state vector
Sinai_Aranda
June 6 |
@ted-miller @gavanderhoorn You could connect to my PC trough of teamviewer with the robot on net, to see the problem.
![]() |
gavanderhoorn
June 6 |
I’m currently abroad on travels and cannot assist you directly. I’ll take a look as soon as I can, which may be this weekend or next week.
To me it’s unclear at the moment whether this is a configuration issue on the controller’s side, or whether the ROS side is faulting.
What you could try for now is see whether this pr improves things. If it does, I’ll have a better idea of what is going on exactly. Note that the PR is slightly behind the state of kinetic-devel
, but that shouldn’t matter for what you’ll be testing iirc.
![]() |
gavanderhoorn
June 6 |
@ted-miller: just looked at the wireshark capture provided by @Sinai_Aranda. Can you comment on the (unexpectedly) large joint velocities reported for axes J4
to J7
for the third group? Those make little sense to me.
They’re in the third SIMPLEMESSAGE
packet of the capture.
![]() |
ted-miller
June 7 |
Based on the wireshark capture, it appears that the robot side is configured correctly. There are three groups and the state appears to be reported correctly (ignoring the velocity data). I do see that [motion_ready] is false… but I assume that’s just because the INIT_ROS job hasn’t been started.
Based on the console output above (all_joint_state.positions: 0 == all_joint_names: 7), I’m speculating one of two things. (But, I fully admit that I don’t know enough about these two things to speak competently; so this is pure speculation.)
In regard to the odd velocity output, I’m not sure. The garbage data only appears on the axes which aren’t used (group 3 is only a single axis). So, I think the problem is that I’m not zero-ing the velocity data prior to calling the mpSvsGetVelTrqFb API. It’s possible that the API is only filling in the first value for the single axis and then ignoring the rest of the values, which is uninitialized data.
![]() |
ted-miller
June 11 |
In regard to the garbage joint velocities, I found this in the reference manual:
“Since the area specified by the parameter is not initialized (0 clear) by this API, initialize the area by the application as necessary.”
So, I just need to clear the data before calling the API. I will fix this in the next commit.
![]() |
Sinai_Aranda
June 11 |
@ted-miller How say PR of @gavanderhoorn:
So, the robot must be configure to station? this way I moved the real robot and rviz same before.
![]() |
ted-miller
June 11 |
If you have a DX100 and a rail, it CANNOT be configured as a base axis if you want to control it with ROS. Instead, you must configure the rail as an external axis
This is apparently not true. andreaskoepf said above that the the SDA should be configured as R1+R2+B1. I have also tested and confirmed that the waist axis should be configured as a base axis.