ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

How to change velocity & acceleration in MotionPlanRequest topic

asked 2017-01-04 19:23:46 -0500

130s gravatar image

updated 2017-02-24 18:07:41 -0500

With the newest version of MoveIt! (Indigo 0.7.6), we can nicely scale the velocity and acceleration of trajectory on MoveIt! RViz plugin. Looking at the Time Parameterization tutorial changing them programmatically during runtime seems also possible by changing MotionPlanRequest.msg, but how exactly can we do so?

Now I'm trying to see using NEXTAGE but I don't see that type of topic being published while MoveIt! is running.

Related question by @robotfan

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2017-01-05 00:47:52 -0500

rbbg gravatar image

It depends on what interface you are using to make the planning request. If you are making the service call yourself, it is trivial to set the max_velocity_scaling_factor and max_acceleration_scaling_factor manually.

When using the the move_group C++ API, you have a function for the velocity and for the acceleration. These updates factors will then be used for the next planning request.

the moveit_commander move_group interface also has these functions (velocity and acceleration)

Setting the acceleration is quite recent for moveit_commander but I'm pretty sure it is in 0.7.6.

edit flag offensive delete link more

Comments

Thanks. set_max_acceleration_scaling_factor is still missing from Indigo, so I opened a PR for it.

130s gravatar image 130s  ( 2017-02-24 21:16:53 -0500 )edit
2

answered 2017-01-06 15:05:47 -0500

The move_group node advertises a "/plan_kinematic_path" service which takes in moveit_msgs/GetMotionPlan service request. You just need to populate the request message with you plan details (including velocity and acceleration scaling) and call the service. There are some useful utility functions that can be used to populate the MotionPlanRequest.msg fields.

edit flag offensive delete link more
0

answered 2017-03-13 21:51:54 -0500

shzargar gravatar image

updated 2017-03-14 00:57:15 -0500

130s gravatar image

I want to use set_max_acceleration_scaling_factor in my python program to control the velocity but I get:

  File "./nextage_moveit_waypoint.py", line 117, in main
    larm.set_max_velocity_scaling_factor(0.5)   
AttributeError: 'MoveGroupCommander' object has no attribute 'set_max_velocity_scaling_factor'

running this : rosversion moveit_commander gives me this: 0.6.1

I tried to do update with sudo apt-get install ros-indigo-moveit-full-pr2 (or sudo apt-get install ros-indigo-moveit) source /opt/ros/indigo/setup.bash

but at the end, rosversion moveit_commander returns me the same version.

How I can update my moveit_commander and make sure that I have set_max_acceleration_scaling_factor

edit flag offensive delete link more

Comments

1

Unfortunately on this type of forums you're not supposed to open a new question on someone else' thread (and you used "answer" section), probably in an attempt to let readers focus on a narrower subject and provider better user support. In this case I opened #q256922 for you.

130s gravatar image 130s  ( 2017-03-14 01:09:58 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-01-04 19:23:46 -0500

Seen: 5,017 times

Last updated: Mar 14 '17