Closed adamlouis closed 2 years ago
Thanks for the detailed issue explanation; I don't see any obvious issues with your approach or your MoveIt config.
MoveIt has some dynamic reconfigure parameters relating to trajectory execution that might be causing your issue. You might try turning off execution_duration_monitoring
or increasing the allowed_execution_duration_scaling
. Your planned trajectory should have time stamps associated with each waypoint (from the time parameterization stage of planning) and MoveIt does some monitoring to make sure that the trajectory execution on the controller actually completes within the amount of time the planned trajectory should have taken (with a scale factor applied to it). Disabling the execution_duration_monitoring
circumvents this check, and increasing the allowed_execution_duration_scaling
increases the scale factor for the trajectory time limit. Making these changes has resolved a similar issue for me recently, but I haven't delved into why this problem exists in the first place since my trajectory seemed to be time parameterized properly
rostopic pub
-ing to an action goal
topic is not a good idea. Not just with motoman_driver
, but in general.
I'd suggest using code similar to what is linked in #229.
I'm slightly confused as well: AFAIK and IIRC, goals with a JointTrajectory
with a single point in them should not be accepted. motoman_driver
absolutely needs two points: current state and destination point. The rostopic pub
command line shown only includes a destination point.
Additionally, I'd suggest to use motoman_gp4_support which provides convenience .launch
files which take care of everything wrt configuration of the driver for this particular robot variant.
Starting the driver then only needs:
roslaunch motoman_gp4_support robot_interface_streaming_gp4.launch robot_ip:=192.168.1.31
controller:=yrc1000
nothing more is needed.
@adamlouis: please try again with just that robot_interface_streaming_gp4.launch
file, nothing else.
And please start it using roslaunch --screen
, and copy-paste the full output from the terminal into a comment here, after you've invoked robot_enable
again and tried to execute a trajectory again (preferably using MoveIt or the action client script linked in #229, not rostopic
).
I'd also suggest updating your ROSCONSOLE_FORMAT
env var to '[${severity}] [${time}] [${node}] [${logger}]: ${message}'
, so it's clear which node printed which line.
Edit: and don't use demo.launch
to control a real robot.
The MoveIt configuration you've shared includes a moveit_planning_execution.launch
. That would be the proper entrypoint normally. I'm not sure how you've changed it, so it could be it's not in working order
@marip8 wrote:
MoveIt has some dynamic reconfigure parameters relating to trajectory execution that might be causing your issue. [...] Making these changes has resolved a similar issue for me recently, but I haven't delved into why this problem exists in the first place since my trajectory seemed to be time parameterized properly
If that was with motoman_driver
, something is wrong, as that should not be necessary.
Unless perhaps the joint limits for the specific robot were not configured correctly and whatever parameterised the trajectory is expecting the robot to be able to move faster than it really can.
If that was with motoman_driver, something is wrong, as that should not be necessary.
Agreed; I'm going to work with the robot more this week, so hopefully I can figure out what is going on. The fix I mentioned might at least get the robot moving in case there are other parameterization/joint velocity limit issues that are MoveIt/URDF related.
Thank you @gavanderhoorn & @marip8 for you quick replies and suggestions!
Here's what I've done & observed:
You might try turning off
execution_duration_monitoring
or increasing theallowed_execution_duration_scaling
I did this by adding these 2 lines to my MoveIt launch file:
<param name="move_group/trajectory_execution/allowed_execution_duration_scaling" value="4.0" />
<param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />
When I do this, I do not get a timeout error, but the robot does not move.
motoman_gp4_support
launch filesAdditionally, I'd suggest to use motoman_gp4_support which provides convenience .launch files which take care of everything wrt configuration of the driver for this particular robot variant.
Starting the driver then only needs:
roslaunch motoman_gp4_support robot_interface_streaming_gp4.launch robot_ip:=192.168.1.31 controller:=yrc1000
nothing more is needed.
done
- update console format
I'd also suggest updating your ROSCONSOLE_FORMAT env var to '[${severity}] [${time}] [${node}] [${logger}]: ${message}', so it's clear which node printed which line.
done
Edit: and don't use demo.launch to control a real robot. The MoveIt configuration you've shared includes a moveit_planning_execution.launch. That would be the proper entrypoint normally. I'm not sure how you've changed it, so it could be it's not in working order
Fair point - I will rename this to something appropriate moving forward.
Likewise, because my MoveIt configuration might be bad, I will use your simple_trajectory_action_client.py
script for further tests.
motoman_gp4_support
launch files + your scriptAnd please start it using roslaunch --screen, and copy-paste the full output from the terminal into a comment here....
Below are the outputs of the 2 terminals - the ROS driver terminal and the simple_trajectory_action_client.py
terminal.
I updated the joint names in simple_trajectory_action_client.py
to match the joint names of my robot.
Likewise, I ran the script several times with small modifications (e.g. move a different joint a different amount) but none worked.
Strangely, the Python script exits with success, but with the ROS log shows the same error line,
[ERROR] [1647298434.963551694] [/motion_streaming_interface] [ros.motoman_driver]: Failed to initialize MotoRos motion, trajectory execution ABORTED. If safe, call the 'robot_enable' service to (re-)enable Motoplus motion and retry.
At the bottom, it shows the line:
[ INFO] [1647298439.967259077] [/joint_trajectory_action] [ros.industrial_robot_client.joint_trajectory_action.controllerStateCB]: Inside goal constraints - stopped moving- return success for action
Which is strange, due to 1) the prior error and 2) the fact that the robot did not move
roslaunch --screen motoman_gp4_support robot_interface_streaming_gp4.launch robot_ip:=192.168.1.31 controller:=yrc1000
python3 simple_trajectory_action_client.py
[INFO] [1647298434.646652] [/simple_trajectory_action_client] [rosout]: Waiting for driver's action server to become available ..
[INFO] [1647298434.928927] [/simple_trajectory_action_client] [rosout]: Connected to trajectory action server
[INFO] [1647298434.958179] [/simple_trajectory_action_client] [rosout]: Submitting goal ..
[INFO] [1647298434.959258] [/simple_trajectory_action_client] [rosout]: Waiting for completion ..
[INFO] [1647298439.968406] [/simple_trajectory_action_client] [rosout]: Done.
Thanks again for your help!
I'm starting to suspect your YRC1000 is somehow not configured correctly.
Could you do one more test with the action client script, and make a wireshark trace of the network traffic between the YRC1000 and your ROS PC at the same time? Then please attach it here (make sure to compress it).
Additionally:
Please also send that CMOS to the Partner Support team in the separate other email chain. They can check to ensure there isn't anything configured that would prevent robot motion.
There is a parallel support effort, next to this thread?
@adamlouis: could you please let us know when that has reached a conclusion?
I'll close this one for now, as I don't like potentially duplicating effort.
@gavanderhoorn: I asked him to open this issue because I didn't see anything wrong with the description of his procedure. It appears that the robot-side is working ok. I figured there was something wrong in the support package that I'm not aware of.
I just wanted to have our support group check to make sure there isn't some safety-circuit configured improperly or something.
Thanks all! I will work on this later today.
I'm starting to suspect your YRC1000 is somehow not configured correctly.
Could you do one more test with the action client script, and make a wireshark trace of the network traffic between the YRC1000 and your ROS PC at the same time? Then please attach it here (make sure to compress it).
Additionally:
could you tell us which INFORM job you've installed from here (there are a couple, and it matters) could you make a CMOS backup, zip it and attach it here?
I will do this after I send the zip to Yaskawa/Motoman partner support & hear back
Please also send that CMOS to the Partner Support team in the separate other email chain. They can check to ensure there isn't anything configured that would prevent robot motion.
Will do later today
There is a parallel support effort, next to this thread?
@adamlouis: could you please let us know when that has reached a conclusion?
I'll close this one for now, as I don't like potentially duplicating effort.
As Ted mentioned - I emailed our contacts at Yaskawa. Over that email, I was asked to open the GitHub issue here. Later, I was asked for the same .zip you requested. I will send my zip to partner support & come back here if needed (or to report a resolution).
FYI - I have been able to get our robot up & running by programming against the YRC1000 ethernet interface. I suspect I will be able to do our initial task with just the ethernet interface. In any case, I would like to figure the ROS configuration out to support more sophisticated use cases as they emerge.
Thanks again!
@ted-miller wrote:
@gavanderhoorn: I asked him to open this issue because I didn't see anything wrong with the description of his procedure. It appears that the robot-side is working ok. I figured there was something wrong in the support package that I'm not aware of.
I just wanted to have our support group check to make sure there isn't some safety-circuit configured improperly or something.
This all makes complete sense, but please ask people to mention that in the initial post.
Especially when things like the CMOS settings haven't been checked yet, as that is almost impossible to diagnose from "the ROS side". Knowing that's being looked at would change the approach to diagnose what's going on.
@adamlouis wrote:
FYI - I have been able to get our robot up & running by programming against the YRC1000 ethernet interface. I suspect I will be able to do our initial task with just the ethernet interface. In any case, I would like to figure the ROS configuration out to support more sophisticated use cases as they emerge.
I would suggest to still create the wireshark trace.
It should not take very long, and there is a good chance we'll be able to diagnose what's going on from that -- provided the CMOS backup shows no problems with the configuration of the YRC1000u itself.
@adamlouis: let us know whether you'll still create the Wireshark trace and we'll re-open.
The support guys found that the Inform job was incorrect. (Sorry, I should have caught that.)
For anyone experiencing similar issue in the future, please use the standard INIT_ROS jobs posted to GitHub. The motion API command will only work if the control-group is being blocked by a WAIT command. This is a safety mechanism to prevent conflicting motion from multiple points of control.
How did that happen?
Was the job not the one we host here?
There were 2 issues. The first is resolved. For the second, I have a work around (or perhaps this is how it must be done).
INIT_ROS
codeWe purchased our GP4 / YRC1000 / SMart Pendant with ROS pre-configured. There was already a INIT_ROS
job present when we received it.
When I sent the back up .zip file of our YRC1000 to the Motoman partner support team, they noticed the error Ted mentioned above.
I edited the job to match what they provided in the email, which matches the code here.
I (or anyone here) did not deliberately edit the INIT_ROS
job after we received our shipment. Though, of course it is possible I did so in error / negligence.
INIT_ROS
does not begin execution and block on a WAIT command except when run from "PLAY" modeAfter editing the job to match the code referenced above, calling rosservice call /robot_enable "{}"
when in REMOTE mode on the Smart Pendant did not advance the Job to the wait instruction.
Rather, I see "INIT_ROS" as the "Current Job" on the smart pendant home screen, but when I view the "Current Job" page, the job is at the "Start Job" instruction.
If I turn the pendant key to PLAY mode and run the INIT_ROS
job manually from the pendant touch screen, the job executes up until the wait instruction.
Then, if I switch the pedant to REMOTE remote mode, run rosserivce call /robot_enable "{}"
, and move the robot in RViz / MoveIt with the config referenced in my initial post, the robot moves as expected.
Thank you all for you support & quick replies while figuring this out!
I realized point 2 in my post above is true when starting other custom pendant jobs with the ethernet interface, not just when starting INIT_ROS
with ROS. I had not observed this behavior when starting custom jobs over ethernet earlier.
It seems I must first go to PLAY mode before starting jobs in REMOTE mode.
In either case, I think I am unblocked & can figure this out.
Thanks all again for your help & for your work on this repo!
You should be able to start everything in REMOTE
mode.
Something does not seem to be right still.
We purchased our GP4 / YRC1000 / SMart Pendant with ROS pre-configured. There was already a INIT_ROS job present when we received it.
This sounds like the error came from our manufacturing area. I'll look into it.
It seems I must first go to PLAY mode before starting jobs in REMOTE mode.
This is not normal. Could you please use Wireshark to record the network traffic when you attempt robot_enable
while in remote mode?
Thanks for the feedback!
I will try to post the wireshark output by EOD tomorrow.
Likewise, I will let you know if we figure out a more minimal set of steps reproduce the behavior.
Friendly ping @adamlouis
@gavanderhoorn & @ted-miller - I've attached a zip of my wireshark traffic here. There was a fair amount of data constantly passing between my compute & the yrc1000, but the capture represents a 5-10s window during which I ran rosservice call /robot_enable "{}"
. The YRC is 192.168.1.31
and my computer is 192.168.1.32
. Let me know if this is what you were looking for.
I can confirm that my ros terminal printed [ros.motoman_driver]: Motoman robot is now enabled and will accept motion commands.
when I issued this command and the robot would not move via rviz/moveit after I did this.
I have consistently reproduced the behavior I described before & have a few more details. My flow is:
roslaunch ...
rosservice rosservice call /robot_enable ...
claims to work here, but actually fails and the robot will not move with RViz / MoveIt ... this call is in my wireshark capture ... the INIT_ROS job is stuck at the first "Start Job" linerosservice rosservice call /robot_enable "{}"
... the INIT_ROS job proceeds to the "Wait ..." line as expectedThe behavior above is true of other custom jobs I wrote and not just INIT_ROS
. If I use the START
command on the ASCII ethernet protocol of the yrc1000 to start my own pendant jobs, I observe the same behavior that those jobs do not start until I toggle the smart pendant to PLAY mode. Again, I don't need to do anything in PLAY mode - simply toggling there & back is enough to make remote invocation of jobs work as expected.
This seems to indicate the issue is with something on the YRC / pendant side vs. on the ROS driver side given that starting jobs in REMOTE mode fails similarly even when not using any of the code in this repo.
Thanks again! Let me know if you have any other experiments / evidence you'd like me to capture.
Seems like MotoROS considers starting INIT_ROS
a success:
ROS-Industrial SimpleMessage, Motoman Motion Reply (0x7d2), 76 bytes, little-endian
Prefix
Packet Length: 72
Header
Message Type: Motoman Motion Reply (0x000007d2)
Communications Type: Service Reply (3)
Reply Code: Success (1)
Body
Robot ID: -1
Sequence Number: -1
Command: Motion_Ctrl (2001)
Result: Success/True (0)
Subcode: Unknown (0)
Data (reserved)
J0: 0,000000000
J1: 0,000000000
J2: 0,000000000
J3: 0,000000000
J4: 0,000000000
J5: 0,000000000
J6: 0,000000000
J7: 0,000000000
J8: 0,000000000
J9: 0,000000000
does imply there is something not entirely correct on the YRC1000 side.
the capture represents a 5-10s window during which I ran rosservice call /robot_enable "{}".
Could have been informative if you'd included the traffic when you're attempting to execute a trajectory, but I'm sort-of expecting to just see acceptance of traj pts until the buffer is full and then nothing.
@adamlouis Can you check that this installation step was done properly:
Controller Configuration
Verify that the controller is enabled to receive remote commands in Remote mode:
Using standard pendant:
Rotate the pendant key-switch (upper left of pendant) fully counter-clockwise into TEACH mode.
Upgrade your Security Level to MANAGEMENT
Touching [System Info]→[Security].
Default password is all 9's. Using the pendant, select [In/OUT]→[PSEUDO INPUT SIG]
For DX100, DX200, and FS100, set input #82015 (CMD REMOTE SEL) to ON. The signal number is #87015 on YRC.
Move the cursor to the circle beside the specified input Press [INTERLOCK]+[SELECT] to turn on the input
Rotate the pendant key-switch (upper left of pendant) fully clockwise into REMOTE mode.
@adamlouis Also check the Operate Enable Settings:
Upgrade your Security Level to MANAGEMENT (as above) Touching [SETUP]→[OPERATE ENABLE]. Make sure that all the operations are set to PERMIT
@adamlouis The wireshark indicates that the robot does briefly become "ready", but then becomes "not ready" 124 ms after the robot_enable service is called. I think there is still something wrong with the robot job.
Could you please save out a fresh copy of the following files and attach them here. Be sure to zip them; they compress extremely well.
INIT_ROS.JBI PANELBOX.LOG ALL.PRM CMOS.BIN
Could you please save out a fresh copy of the following files...
done!
Using the pendant, select [In/OUT]→[PSEUDO INPUT SIG] For DX100, DX200, and FS100, set input #82015 (CMD REMOTE SEL) to ON. The signal number is #87015 on YRC. Move the cursor to the circle beside the specified input Press [INTERLOCK]+[SELECT] to turn on the input
Touching [SETUP]→[OPERATE ENABLE]. Make sure that all the operations are set to PERMIT
@EricMarcil -- I referenced this in my initial post & the private email thread, but I am using a smart pendant and not a standard pendant. I have not found PSUEDO INPUT SIG
, CMD REMOTE SEL
, INTERLOCK
, or SETUP
on the smart pendant and have not seen a value of 87015 (or values w/ this order of magnitude) on any IO screen.
Do you have documentation to accomplish this with the smart pendant rather than the standard pendant?
Are you able to read the necessary data from the system backup rather than the pendant UI?
For my own reference -- are the smart pendant & standard pendant two clients of the same controller core, or do the two pendants require different controller configuration?
Thank you!
It's (almost certainly) not the cause of the problem, but I notice you're running MotoROS v1.9.0
.
That's rather old, as the current version would be v1.9.10
.
You might want to upgrade. The binaries can be found here for the YRC1000u.
I have not found PSUEDO INPUT SIG, CMD REMOTE SEL, INTERLOCK, or SETUP on the smart pendant and have not seen a value of 87015 (or values w/ this order of magnitude) on any IO screen. Do you have documentation to accomplish this with the smart pendant rather than the standard pendant?
This step is not required for the Smart Pendant. The signal must already be enabled for the SP to work. I have updated the installation instructions to hopefully make this clearer.
For my own reference -- are the smart pendant & standard pendant two clients of the same controller core, or do the two pendants require different controller configuration?
They are two clients of the same controller core.
Are you able to read the necessary data from the system backup rather than the pendant UI?
Yes. I have found the problem. The job is set to "step" mode where it only executes one step at a time. (I didn't know this was a thing, nor can I explain why it behaves differently in PLAY mode.)
Smart Pendant instructions: (The installation wiki has been updated with instructions for both pendant types.)
Rotate the pendant key-switch (top of pendant) to the middle position for PLAY mode.
Touch [MENU]→[Job List]
Select the INIT_ROS job from the list and touch the [RUN] button in the lower left.
In the ADVANCED RUN pane, change the Mode
to One Cycle
.
Rotate the pendant key-switch (top of pendant) fully clockwise into REMOTE mode.
@adamlouis: I just learned some new information about this issue. The instructions above are not sufficient long-term. It will automatically switch back to STEP
mode when you toggle the key switch.
Touch MENU
> System Settings
> Classic Interface
. Start the Classic Interface and press the Connect
button.
From the main menu, touch Setup
> Operate Cond
. Cursor down to the Cycle Switch In xxxx Mode
fields. Change all of these to CYCLE
.
The touch the power-symbol button in the top right to return back to the Smart Pendant interface.
@adamlouis: have you had a chance to figure this out? The last comment(s) by @ted-miller should help with the STEP
mode problem.
Assuming this has been fixed, I'm going to close the issue.
Please let us know your current status @adamlouis.
Hi! I am trying to get a new GP4 robot working with ROS + MoveIt using a YRC1000micro controller.
I can't get to the robot to move ... but I seem close. I would appreciate any help or debugging steps to get our robot moving.
We purchased our robot with the ROS package installed.
summary
Failed to initialize MotoRos motion, trajectory execution ABORTED. If safe, call the 'robot_enable' service to (re-)enable Motoplus motion and retry.
rostopic
commands fail with the same errorrosservice call /robot_enable "{}"
and calling it again does not change the behaviorWhy can't I move the robot?
What simple test can I run to verify configuration of remote control of the GP4 over ROS with the YRC1000?
details
1. set up motoman driver
First, I followed the instructions here: https://wiki.ros.org/motoman_driver/Tutorials/Usage
I start roscore in terminal 1
terminal 1
then, I load the gp4 urdf & joint names
command terminal
then, I run the driver for our controller w/ the robot's pre-set IP
terminal 2
2. run a moveit config
next, I run my move it configuration.
I adapted my configuration from this one in
motoman_experimental
: https://github.com/ros-industrial/motoman_experimental/tree/kinetic-devel/motoman_mpl80_moveit_configMy modifications were:
mpl80
withgp4
motoman_mpl_support
withmotoman_gp4_support
mpl80
urdf & srdf withgp4
urdf & srdffake_execution
andsim
... because I am trying to test a real robotI forked the
motoman_experimental
repo and created a branch here with my motoman_gp4_moveit_config configuration: https://github.com/adamlouis/motoman_experimental/tree/motoman_gp4_moveit_config/motoman_gp4_moveit_configI would be happy to clean that up & find a way to include it in motoman_experimental when I figure out what's wrong.
then, I run it with
terminal 3
at this point, if I move the robot using our teach pendant, the movement is reflected in Rviz.
this is good & tells me that I am able to read state from the yrc1000micro.
3. prepare for execution
now, I am ready to move the robot
command terminal
I hear relays click and see the servo lights turn on
output in command terminal
output in terminal 2
This is good - in theory, I can move the robot.
4. Try to move with RViz + MoveIt
I try to move the robot 2 ways & get the same behavior.
First, in Rviz + MoveIt, I set a goal position. I choose a goal position only small distance from the current position. I click "Plan" and "Execute".
On "Execute", I get the following output:
output in terminal 2
output in terminal 3
If I run the command to enable the service
command terminal
& repeat the above steps, I get the same error.
5. Try to move with
rostopic
It's possible I wrote a bad moveit config, so I try to run some trivial command to move the robot with ROS.
The easiest thing seemed like:
rostopic pub /joint_trajectory_action/goal control_msgs/FollowJointTrajectoryActionGoal
. Is there some simpler command to test "write" commands to the yrc1000 over ROS?This command fails with the same errors as above:
output in terminal 2
output in terminal 3
Here's my full command. The positions I provide are the robot's current positions.
Some notes:
INIT_ROS
is the "Current Job" on the teach pendantSVO
andSTART
- which implies to me remote control is okCMD REMOTE SEL
is set to "valid" in the pseudo input display per page 22 / 291 of the "YRC1000micro OPTIONS INSTRUCTIONS for Ethernet Function". We have a different teach pendant than is referenced in the documentation & I have not found this setting. Is this related? I suspect I am ok, since I could start jobs over the ethernet protocolrobot_interface_streaming_yrc1000.launch
. The warnings seem fine & the errors seems fine per @gavanderhoorn's reply in https://github.com/ros-industrial/motoman/issues/242 & https://github.com/ros-industrial/motoman/issues/235 ...Thanks for reading & thanks in advance for any help! Would appreciate any pointers to help get us up an running.