Rviz Motion Planning - Path Constraints

620 views
Skip to first unread message

jz...@swri.org

unread,
May 23, 2013, 2:38:08 PM5/23/13
to moveit...@googlegroups.com
I'm exploring the different options available for Motion Planning using the rviz plugin.

I see under the Planning tab, there is a drop-down list for "Path Constraints", but my list only contains a single item: "None".

Is there a way to set Path Constraints from within rviz?  Where is this list populated from?  How do I create constraints that show up in this list?

Thanks!
  Jeremy Zoss
  Southwest Research Institute

Ioan Sucan

unread,
May 23, 2013, 3:14:23 PM5/23/13
to jz...@swri.org, moveit...@googlegroups.com
Jeremy,

That part connects to the moveit warehouse. If you are connected to the warehouse database (first tab of the plugin), the constraints table is read and the names of the constraints are used to populate the list you mention.
Note: planning with constraints requires a fast IK solver that is also able to find the solution nearest to the seed state.


Populating that database can be done programmatically using the ConstraintsStorage class. For an example,  take a look at moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp
There is also a launch file in your config package: default_warehouse_db.launch;
If you run that with the reset argument set to true:
roslaunch your_moveit_config_pkg default_warehouse_db.launch reset:=true

A database will be initialized for you with a demo orientation constraint for each group that has an end effector associated to it. In the case of the PR2  this ends up being an upright constraint, but you will probably need to change that for your robot.

Ioan

Reply all
Reply to author
Forward
0 new messages