moveit_ros icon indicating copy to clipboard operation
moveit_ros copied to clipboard

Specifying the time for a goal is not possible

Open awesomebytes opened this issue 10 years ago • 16 comments

As stated in this thread: https://groups.google.com/forum/#!topic/moveit-users/J8Tdtut8P10

Some people are interested (myself included) in recovering the field where you could specify the time a plan should take like in move_arm.

awesomebytes avatar Nov 15 '13 08:11 awesomebytes

Yes, this would be a very welcome enhancement. In the meantime, I was trying to do it myself (in Python) by modifying the time_to_start for each point in the trajectory--something I was able to do back in an earlier Groovy version--but now I get an error because the trajectory points are apparently an immutable tuple rather than a list. Did this change at some point?

pirobot avatar Dec 01 '13 15:12 pirobot

A longer time_from_start also means lower velocities and accelerations at the waypoints, so if you're modifying only the time_from_start of a waypoint containing a velocity and acceleration spec, you won't get the warping you expect.

adolfo-rt avatar Dec 02 '13 10:12 adolfo-rt

Sorry--I should have been more specific. I am indeed modifying speeds and accelerations as follows:

    # plan the trajectory
    traj = self.right_arm.plan()

    # Alter the trajectory speed if desired
    new_traj = RobotTrajectory()
    new_traj = traj

    n_joints = len(traj.joint_trajectory.joint_names)
    n_points = len(traj.joint_trajectory.points)

    spd = 3.0

    points = list(traj.joint_trajectory.points)

    for i in range(n_points):
        point = JointTrajectoryPoint()
        point.time_from_start = traj.joint_trajectory.points[i].time_from_start / spd
        point.velocities = list(traj.joint_trajectory.points[i].velocities)
        point.accelerations = list(traj.joint_trajectory.points[i].accelerations)
        point.positions = traj.joint_trajectory.points[i].positions

        for j in range(n_joints):
            point.velocities[j] = point.velocities[j] * spd
            point.accelerations[j] = point.accelerations[j] * spd

        points[i] = point

    new_traj.joint_trajectory.points = points

    # execute the trajectory
    self.right_arm.execute(new_traj)

pirobot avatar Dec 03 '13 15:12 pirobot

Hey @pirobot. It's good that you're scaling velocities by spd, but in order to preserve the trajectory shape, you should be scaling accelerations quadratically, by spd^2.

adolfo-rt avatar Dec 03 '13 16:12 adolfo-rt

@adolfo-rt - Good catch! And thanks!

pirobot avatar Dec 03 '13 17:12 pirobot

Are there still plans to implement this enhancement?

pirobot avatar Mar 12 '14 22:03 pirobot

Any news on this ?

thiagoribeirodamotta avatar Apr 15 '14 16:04 thiagoribeirodamotta

+1 for this feature!

ZdenekM avatar Sep 04 '14 12:09 ZdenekM

Anybody has pulled this off?

anderwm avatar Jun 29 '16 20:06 anderwm

The discussion on this seems to vary between

  • "go as fast as you can" ... This is what the current AddTimeParametrization does, it is based on the velocity bounds specified for the joints
  • "add a scaling factor" ... this has been done for values (0;1]
  • "add a latest end-time to the planning request" ... Does this even make sense? It would include the planning time
  • "add the duration of the final motion to the planning request" ... Does this make sense? We don't know the motion of the request in advance, so how would you reasonably specify the duration?

At the moment, I believe this issue, as far as it should be implemented in MoveIt, is resolved by #547. Are there other opinions?

v4hn avatar Jul 07 '16 11:07 v4hn

Does this allow you to add the scaling factor after the plan has been made (but before execution)? I imagine typical use case is:

  • Plan a path at max speed
  • Look at the time predicted to execute the plan
  • Decide how long you actually want it to take and scale appropriately

I can't tell immediately from #547 code if you have to set the scaling factor before planning. If you can scale the plan before execution then it solves the problem for me.

anderwm avatar Jul 07 '16 12:07 anderwm

On Thu, Jul 07, 2016 at 05:54:31AM -0700, anderwm wrote:

Does this allow you to add the scaling factor after the plan has been made (but before execution)?

Well, technically it is applied after planning (in a PlanningRequestAdapter), but the factor has to be specified in the request already. So this probably does not fit your purpose.

  • Decide how long you actually want it to take and scale appropriately

Depending on your needs you could plan beforehand using move_group_interface::MoveGroup::plan and then decide whether you still want to execute the trajectory, scale it appropriately and move_group_interface::MoveGroup::execute it. This would only require a scaling function exposed by MoveIt to scale moveit_msgs::RobotTrajectory or robot_trajectory::RobotTrajectory by some time factor. Such a function might be nice to have anyway and would go nicely into https://github.com/ros-planning/moveit_core/blob/jade-devel/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h .

On the other hand, I agree that this sounds like a straightforward thing to implement in a PlanningRequestAdapter. And to make the requested ending-time of the trajectory available to the adapter, it would have to be specified in the MotionPlanRequest (which is what this issue proposes). I'm not a fan of that idea though, because if you specify the time before planning the trajectory, the time required to plan the trajectory has to be accounted for. But this can be quite different across various requests and depends on the configured planner. What do you think?

v4hn avatar Jul 07 '16 18:07 v4hn

Depending on your needs you could plan beforehand using move_group_interface::MoveGroup::plan and then decide whether you still want to execute the trajectory, scale it appropriately and move_group_interface::MoveGroup::execute it. This would only require a scaling function exposed by MoveIt to scale moveit_msgs::RobotTrajectory or robot_trajectory::RobotTrajectory by some time factor.

This sounds like what I had in mind. It seems like once you have a planned trajectory based on joint limits, it would be relatively straight forward to make it slower based on a time scale factor (0:1]. Although now that I think about it, you would also have to scale the accelerations by x^2 to be totally precise. This allows the user to coordinate movements between move_groups in a way that I don't think is very easy right now.

On the other hand, I agree that this sounds like a straightforward thing to implement in a PlanningRequestAdapter. And to make the requested ending-time of the trajectory available to the adapter, it would have to be specified in the MotionPlanRequest (which is what this issue proposes). I'm not a fan of that idea though, because if you specify the time before planning the trajectory, the time required to plan the trajectory has to be accounted for. But this can be quite different across various requests and depends on the configured planner. What do you think?

Possibly somebody can tell us, but I don't see why you need this if you have what we mentioned above. I'd rather the planner just return me what is possible and me tell it "yeah, that but slower" than me having to know what is possible in advance. It seems like you will run into many failed plans due to your timing constraint when say an obstacle gets in the way or what have you.

anderwm avatar Jul 07 '16 22:07 anderwm

On Thu, Jul 07, 2016 at 03:29:00PM -0700, anderwm wrote:

[...] This would only require a scaling function exposed by MoveIt to scale moveit_msgs::RobotTrajectory or robot_trajectory::RobotTrajectory by some time factor.

This sounds like what I had in mind. It seems like once you have a planned trajectory based on joint limits, it would be relatively straight forward to make it slower based on a time scale factor (0:1]. Although now that I think about it, you would also have to scale the accelerations by x^2 to be totally precise.

Could you implement such function in the trajectory_processing library and provide a pull-request? This could be a nice addition to the trajectory_tools. The function is not totally trivial and it would be great to have a reviewed implementation of it provided in MoveIt. That would be really awesome!

Possibly somebody can tell us, but I don't see why you need this if you have what we mentioned above.

We probably don't. But that's what the original author of this issue and earlier discussion proposed. :)

I'd rather the planner just return me what is possible and me tell it "yeah, that but slower" [...]

This is exactly what I sketched out.

v4hn avatar Jul 08 '16 10:07 v4hn

I will give it a look to see what is involved. However, my main development machine is on Xenial so I can't actually test, or even compile moveit right now.

anderwm avatar Jul 08 '16 12:07 anderwm

Thanks!

we are working on full kinetic support, and if you feel adventurous, here's the ticket: https://github.com/ros-planning/moveit_ros/issues/695 :-)

v4hn avatar Jul 08 '16 13:07 v4hn