I have some questions regarding trajectory speed.
How are joint speeds chosen in
interfaces.BaseManipulation.MoveManipulator()? I hope the max velocities and accelerations from the robot XML are obeyed.
Does it create a trapezoidal velocity profile? Does it move the joints at max speed? I found this function for retiming a trajectory, which is (I think) the proper way for specifying the joint speeds after planning: planningutils.RetimeTrajectory() But I am a little confused by its arguments and output. Here is how I use it: manipprob = interfaces.BaseManipulation(robot) traj = manipprob.MoveManipulator(goal=goal, outputtrajobj=True, execute=False) waypoints = traj.GetWaypoints2D(0, traj.GetNumWaypoints()) planningutils.RetimeTrajectory(traj, hastimestamps=False, maxvelmult=0.5, maxaccelmult=0.5) new_waypoints = traj.GetWaypoints2D(0, traj.GetNumWaypoints()) Are maxvelmult and maxaccelmult really multiplication factors? If I pass in
maxvelmult=1
and maxaccelmult=1, I get out a different trajectory
with different velocities and timings. I am unclear on the purpose of
hastimestamps. The function fails if I specify this as True. Even though my input trajectory does have timestamps.
It seems to me that when re-timing a trajectory you will always want to override the timestamps. Also, the format of the 2D waypoints is different after the retiming. waypoints[0] has 16 values. (7 positional, 7 velocity, 1 delta time, 1 is waypoint). Whereas
new_waypoints[0] has 15 values. (7 positional, 7 velocity, 1 delta time). is this by design? Thanks, Ben Ben Axelrod Sr. Robotics Software Engineer iRobot Corporation 8 Crosby Drive, M/S 8-1 Bedford, MA 01730 (781) 430-3315 ------------------------------------------------------------------------------ BPM Camp - Free Virtual Workshop May 6th at 10am PDT/1PM EDT Develop your own process in accordance with the BPMN 2 standard Learn Process modeling best practices with Bonita BPM through live exercises http://www.bonitasoft.com/be-part-of-it/events/bpm-camp-virtual- event?utm_ source=Sourceforge_BPM_Camp_5_6_15&utm_medium=email&utm_campaign=VA_SF _______________________________________________ Openrave-users mailing list [hidden email] https://lists.sourceforge.net/lists/listinfo/openrave-users |
I just dug through this code myself, so I'll do my best to answer your
questions. > How are joint speeds chosen in interfaces.BaseManipulation.MoveManipulator()? > I hope the max velocities and accelerations from the robot XML are obeyed. > Does it create a trapezoidal velocity profile? Does it move the joints at > max speed? I believe MoveManipulator() calls MoveActiveJoints(), which calls a BiRRT planner. The planner produces a geometric path with no timestamps and passes it to any algorithms specified in "postprocessingparameters" before returning. By default, the post-processing planner is a ParabolicSmoother which simultaneously shortcuts and times the trajectory. The ParabolicSmoother computes the optimal timing of the input path subject to velocity and acceleration constraints. The output is a trajectory with a trapezoidal velocity profile. > I found this function for retiming a trajectory, which is (I think) the > proper way for specifying the joint speeds after planning: > planningutils.RetimeTrajectory() RetimeTrajectory (and its sister, SmoothTrajectory) is helper function for calling an OpenRAVE::PlannerBase as a trajectory retimer. This is roughly equivalent to creating an empty PlannerParameters structure, calling SetConfigurationSpecification() on it, and passing in trajectory as input. By default, RetimeTrajectory calls ParabolicRetimer. This computes the optimal timing of an input path _without_ shortcutting. The output trajectory must stop at every waypoint. > Are maxvelmult and maxaccelmult really multiplication factors? If I pass in > maxvelmult=1 and maxaccelmult=1, I get out a different trajectory with > different velocities and timings. Yes. The RetimeTrajectory function simply scales the robot's velocity and acceleration limits by these multiples before calling the planner. I'm not sure why this is a feature. > I am unclear on the purpose of hastimestamps. The function fails if I > specify this as True. Even though my input trajectory does have timestamps. > It seems to me that when re-timing a trajectory you will always want to > override the timestamps. In most situations you want to pass hastimestamps=False. In theory, you can use hastimestamps=True to compute the velocity ramps necessary to hit a waypoint at a particular time (if it is possible to due so under the velocity and acceleration constraints). I've never done this, so I have no idea if it works. > Also, the format of the 2D waypoints is different after the retiming. > waypoints[0] has 16 values. (7 positional, 7 velocity, 1 delta time, 1 is > waypoint). Whereas new_waypoints[0] has 15 values. (7 positional, 7 > velocity, 1 delta time). is this by design? In general, I don't think it's safe to assume anything specific implementation details about the ConfigurationSpecification that comes out of a planner. I don't know specifically why it changes in this case, though. Rosen will have to answer your other questions. :-) -Michael ------------------------------------------------------------------------------ BPM Camp - Free Virtual Workshop May 6th at 10am PDT/1PM EDT Develop your own process in accordance with the BPMN 2 standard Learn Process modeling best practices with Bonita BPM through live exercises http://www.bonitasoft.com/be-part-of-it/events/bpm-camp-virtual- event?utm_ source=Sourceforge_BPM_Camp_5_6_15&utm_medium=email&utm_campaign=VA_SF _______________________________________________ Openrave-users mailing list [hidden email] https://lists.sourceforge.net/lists/listinfo/openrave-users |
Administrator
|
hi guys, thanks for the great answers michael!MoveManipulator/MoveActiveJoints/RRT planning all use the robot's max velocity and acceleration RetimeTrajectory is used when there's a path and that's not going to change, but you need to get a robot to follow that path. Right now calling parabolicretimer on a path would give you a trajectory that stops at every waypoint. The velmult and accelmult are just helper functions of changing the robot's max velocity/acceleration temporarily just for the path. Without them, you would have to call SetDOFVelocityLimits/SetDOFAccelerationLimits with a KinBody:: hastimestamps is actually very useful. imagine you have a path with waypoints, and you want all the waypoints to be hit at a specific time (ie for continuous-point control like laser cutting). specifying a path with hastimestamps allows openrave to validate whether that path is possible by the robot. about configurationspecification format, like michael said, you should never assume a specific structure and always use the correct FindGroup and Extract functions to get your data. best, 2015-04-21 10:47 GMT+09:00 Michael Koval <[hidden email]>: I just dug through this code myself, so I'll do my best to answer your ------------------------------------------------------------------------------ One dashboard for servers and applications across Physical-Virtual-Cloud Widest out-of-the-box monitoring support with 50+ applications Performance metrics, stats and reports that give you Actionable Insights Deep dive visibility with transaction tracing using APM Insight. http://ad.doubleclick.net/ddm/clk/290420510;117567292;y _______________________________________________ Openrave-users mailing list [hidden email] https://lists.sourceforge.net/lists/listinfo/openrave-users |
Free forum by Nabble | Edit this page |