This is a Waypoints planning RViz plugin for MoveIt. I decided to create a tab page within "MotionPlanning" plugin rather than to create a separate panel because the latter solution will take further more space in RViz's window. Moreover, as a tab page, its implementation can take advantage of reusing the existing facilities.
With this tab, user can provide a set of points to plan a go-through trajectory with the Cartesian Space.
File | Plugin | Class | Comment |
---|---|---|---|
motion_planning_display.h motion_planning_display.cpp | motion_planning | refactor | added visualize function for waypoints |
motion_planning_frame.h motion_planning_frame.cpp | motion_planning | refactor | forward declaration of tab waypoints added signal callback of tab waypoints overridden computeCartesianPlan |
motion_planning_frame_planning.cpp | motion_planning | refactor | override computeCartesianPlan |
CMakeLists.txt | motion_planning | refactor | new file's manifest |
motion_planning_frame_waypoints.h motion_planning_frame_waypoints.cpp | motion_planning | new | properties and behaviors of widgets of tab waypoints ux logic |
motion_planning_rviz_plugin_frame_waypoints.ui | motion_planning | new | ui from QT Designer |
whi_logo.png | motion_planning | new | logo image |
In this case, just clone this repository, replace the "visualization, " and then build.
First, neutralize the installed libs: "libmoveit_motion_planning_rviz_plugin.so" and "libmoveit_motion_planning_rviz_plugin_core.so"
sudo mv /opt/ros/melodic/lib/libmoveit_motion_planning_rviz_plugin.so /opt/ros/melodic/lib/libmoveit_motion_planning_rviz_plugin.so.bk
sudo mv /opt/ros/melodic/lib/libmoveit_motion_planning_rviz_plugin_core.so /opt/ros/melodic/lib/libmoveit_motion_planning_rviz_plugin_core.so.bk
Then, clone the branch "melodic" of this repository to the src folder of your workspace
cd <your_workspace>/src
git clone https://github.com/xinjuezou-whi/moveit_ros_visualization.git
and build
cd ..
catkin build
or
catkin_make
depends on your environment. And do not forget to source your workspace
source <your_workspace>/devel/setup.bash
NOTE: please refer to ruckig for its installation if MoveIt source is based on version 1.1.11 which depends on ruckig
Once the build is finished, the tab "Waypoints" will be loaded following the "Planning" while running the MoveIt launch file. Let's take the panda_moveit_config as an example:
cd <your_workspace>
roslaunch panda_moveit_config demo.launch
For a real-world arm, given the plan operation is succeed, check the "Loop Execution" and then execute, the arm will repeat the planned trajectory.
There are two ways to add a point from the current goal state of eef. One is to check the "current" before clicking the "Add" or "Insert" button. And the other is to right-click the added point in the waypoints list, then click "current" on pop-up menu.
The Interactive Marker Size property in the category Waypoints can be used to adjust the marker size of waypoint, if it is too small to be selected:
- save waypoints to the file, and load them from the saved file
- ...