ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
When I am running the node, my robotic arm is performing only first trajectory .
(note: I'll assume that trajectory here should actually read trajectory point)
This is a guess, but I believe the following may explain what you observe:
command
topic. This is a fire-and-forget interface to the JointTrajectoryController
, meaning you get no feedback and are responsible yourself to make sure "the current trajectory" has finished executing before sending a new onewhile
-loop in your main(..)
causes the same trajectory to be published again and again at a frequency of 10 HzTaking all of this together, it's possible that what you see is completely according to how the JointTrajectoryController
is specced to work:
time_from_start
always set to 1.0
1.0 / 10 == 0.1
< 1.0
, the first point of the trajectory will always be the destination pointIn essence, you're giving the JointTrajectoryController
a single destination (the first point in the trajectory) and always 1 second to reach it and tell it to go again to that point at a frequency of 10 Hz.
The other two trajectories are performed when I am pressing
ctrl+c
command
(again: I'll assume that trajectory here should actually read trajectory point)
This can be explained by the fact that once you stop your script, the JointTrajectoryController
finally gets a chance to completely execute the trajectory (ie: without any replacement trajectories coming in), so it will (should) reach points 2 and 3 in 2 and 3 seconds respectively.
Finally: as I wrote in my initial comment: it's ok to use the command
interface/topic, but you'll have to make sure the controller has executed the trajectory before sending a new one (or actually make use of the replacement capabilities of course).
If you're not interested in replacement, I would suggest you instead use the action interface which lets you wait on completion of a goal, notifying you when it's ok to send a new trajectory.
2 | No.2 Revision |
When I am running the node, my robotic arm is performing only first trajectory .
(note: I'll assume that trajectory here should actually read trajectory point)
This is a guess, but I believe the following may explain what you observe:
command
topic. This is a fire-and-forget interface to the JointTrajectoryController
, meaning you get no feedback and are responsible yourself to make sure "the current trajectory" has finished executing before sending a new onewhile
-loop in your main(..)
causes the same trajectory to be published again and again at a frequency of 10 HzTaking all of this together, it's possible that what you see is completely according to how the JointTrajectoryController
is specced to work:
time_from_start
always set to 1.0
1.0 / 10 == 0.1
< 1.0
, the first point of the trajectory will always be the destination pointIn essence, you're giving the JointTrajectoryController
a single destination (the first point in the trajectory) and always 1 second to reach it and tell it to go again to that point at a frequency of 10 Hz.
The other two trajectories are performed when I am pressing
ctrl+c
command
(again: I'll assume that trajectory here should actually read trajectory point)
This can be explained by the fact that once you stop your script, the JointTrajectoryController
finally gets a chance to completely execute the trajectory (ie: without any replacement trajectories coming in), so it will (should) reach points 2 and 3 in 2 and 3 seconds respectively.
Finally: as I wrote in my initial comment: it's ok to use the command
interface/topic, but you'll have to make sure the controller has executed the trajectory before sending a new one (or actually make use of the replacement capabilities of course).
If you're not interested in replacement, I would suggest you instead use the action interface which lets you wait on completion of a goal, notifying you when it's ok to send a new trajectory.