Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Build Support for Noetic #73

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 5 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,19 +1,17 @@
# reuleaux
=====
[![Build Status](https://travis-ci.com/ros-industrial-consortium/reuleaux.svg?branch=master)](https://travis-ci.com/ros-industrial-consortium/reuleaux)

Google Summer of Code Project: Robot reachability and Base Placement


[Franz Reuleaux] (https://en.wikipedia.org/wiki/Franz_Reuleaux): *Franz Reuleaux (30 September 1829 -20 August 1905) was a lecturer of the Berlin Royal Technical Academy where he was later appointed as the President. He was often referred as the “father of kinematics”. After becoming a professor at the Swiss Federal Institute of Zurich, he became Rector at Königs Technischen Hochschule Berlin – Charlottenburg. Despite his involvement in German politics he became widely-known as an engineer-scientist, professor and industrial consultant, education reformer and leader of technical elite of Germany. He was also a member of Royal Swiss Acedemy of Sciences.
[Franz Reuleaux](https://en.wikipedia.org/wiki/Franz_Reuleaux): *Franz Reuleaux (30 September 1829 -20 August 1905) was a lecturer of the Berlin Royal Technical Academy where he was later appointed as the President. He was often referred as the “father of kinematics”. After becoming a professor at the Swiss Federal Institute of Zurich, he became Rector at Königs Technischen Hochschule Berlin – Charlottenburg. Despite his involvement in German politics he became widely-known as an engineer-scientist, professor and industrial consultant, education reformer and leader of technical elite of Germany. He was also a member of Royal Swiss Acedemy of Sciences.
Reuleaux relied deeply on the concept of kinematic chain which could be abstracted in kinematic pairs- chains of elementary links. Constraints on each kinematic pairs can lead to constraints on whole machine. He is best remembered for Reuleaux triangle and the development of compact symbolic notion to describe the topology of very wide variety of mechanisms.*



Documentation about Map creation can be found at: [map_creator] (https://github.com/ros-industrial-consortium/reuleaux/tree/master/map_creator)
Documentation about Map creation can be found at: [map_creator](map_creator/README.md)

Documentation about Workspace Visualization can be found at: [workspace_visualization] (https://github.com/ros-industrial-consortium/reuleaux/tree/master/workspace_visualization)
Documentation about Workspace Visualization can be found at: [workspace_visualization](workspace_visualization/README.md)

Documentation about Base Placement Planner can be found at: [Base Placement Plugin] (https://github.com/ros-industrial-consortium/reuleaux/tree/master/base_placement_plugin)
Documentation about Base Placement Planner can be found at: [Base Placement Plugin](base_placement_plugin/README.md)

Please refer to [http://wiki.ros.org/reuleaux] (http://wiki.ros.org/reuleaux) for detailed description and instructions.
Please refer to [http://wiki.ros.org/reuleaux](http://wiki.ros.org/reuleaux) for detailed description and instructions.
28 changes: 21 additions & 7 deletions base_placement_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,18 @@ find_package(catkin REQUIRED COMPONENTS
moveit_core
)

find_package(Qt4 COMPONENTS QtCore QtGui REQUIRED)
if(rviz_QT_VERSION VERSION_LESS "5")
find_package(Qt4 ${rviz_QT_VERSION} REQUIRED QtCore QtGui)
include(${QT_USE_FILE})
set(QT_LIBRARIES )
else()
find_package(Qt5 ${rviz_QT_VERSION} REQUIRED Core Widgets Concurrent)
set(QT_LIBRARIES Qt5::Core Qt5::Widgets Qt5::Concurrent)
endif()
# Instruct CMake to run moc automatically when needed.
set(CMAKE_AUTOMOC ON)

include(${QT_USE_FILE})
find_package(HDF5 REQUIRED)


add_definitions(-DQT_NO_KEYWORDS)
Expand All @@ -39,7 +48,6 @@ set(base_placement_plugin_SRCS
src/place_base.cpp
src/add_robot_base.cpp


${MOC_FILES}
)

Expand Down Expand Up @@ -77,12 +85,18 @@ catkin_package(
map_creator
)

qt4_wrap_cpp(base_placement_plugin_MOCS ${base_placement_plugin_HDRS} )
qt4_wrap_ui(base_placement_plugin_UIS_H ${base_placement_plugin_UIS} )
if(rviz_QT_VERSION VERSION_LESS "5")
qt4_wrap_cpp(base_placement_plugin_MOCS ${base_placement_plugin_HDRS} )
qt4_wrap_ui(base_placement_plugin_UIS_H ${base_placement_plugin_UIS} )
else()
qt5_wrap_cpp(base_placement_plugin_MOCS ${base_placement_plugin_HDRS} )
qt5_wrap_ui(base_placement_plugin_UIS_H ${base_placement_plugin_UIS} )
endif()


include_directories(${base_placement_plugin_INCLUDE_DIRECTORIES} ${catkin_INCLUDE_DIRS})
include_directories(${base_placement_plugin_INCLUDE_DIRECTORIES} ${catkin_INCLUDE_DIRS} ${HDF5_INCLUDE_DIRS})
add_library(${PROJECT_NAME} ${base_placement_plugin_SRCS} ${base_placement_plugin_MOCS} ${base_placement_plugin_UIS_H}) # ${base_placement_plugin_UIS_H}
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY} yaml-cpp -lhdf5 -lhdf5_cpp create_marker)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY} ${QT_LIBRARIES} yaml-cpp ${HDF5_LIBRARIES} create_marker)
## target_link_libraries(${PROJECT_NAME} yaml-cpp)


Expand Down
19 changes: 11 additions & 8 deletions base_placement_plugin/README.md
Original file line number Diff line number Diff line change
@@ -1,20 +1,21 @@
## Base Placement plugin
====
Please refer to [ros wiki] (http://wiki.ros.org/reuleaux) for more detailed instruction

#1. RViz and RQT User Interface:
Please refer to [ros wiki](http://wiki.ros.org/reuleaux) for more detailed instruction

# 1. RViz and RQT User Interface:

There are two types of interactive markers:
- The red arrow acts as a pointer which the user can move around the RViz enviroment. Fruthermore by clicking on the arrow another magenta arrow is added to the RViz enviroment. This arrow acts as task poses for base placement planner.
- The red arrow acts as a pointer which the user can move around the RViz environment. Fruthermore, by clicking on the arrow another magenta arrow is added to the RViz environment. This arrow acts as task poses for base placement planner.
- The magenta arrow is the task poses for the base placement planner. The orientation of the arrow can be changed by holding the CTRL key and moving it with the mouse.
- Each arrow has a menu where the user can either delete the selected arrow or it can change its position and orientation by using the 6DOF marker control.
- The RQT UI communicates simultaniously with the RViz enviroment and the User can change the state of a marker either through RViz or the RQT UI
- The RQT UI communicates simultaneously with the RViz environment and the User can change the state of a marker either through RViz or the RQT UI
- TreeView displays all the added waypoints. The user can manipulate them directly in the TreeView and see their position and orientation of each waypoint.
- The user can add new point or delete it through the RQT UI.
- New tool component has been added for adding Arrows by using a mouse click

#2. How to run the code
Just run rosrun rviz rviz
# 2. How to run the code

Just run `rosrun rviz rviz`

- From the panel window select base placement planner
- Add a reachability map display and set the topic to /reachability_map
Expand All @@ -25,16 +26,18 @@ There is a preconfigured rviz config file in the rviz folder

After deciding the task poses load an inverse reachability map previously created. If you have not done it yet, run

```
rosrun map_creator create_inverse_reachability_map <name of the reachability map>

rosrun map_creator create_inverse_reachability_map /home/abhi/Desktop/motomap_mh5_r0.08_reachability.h5
```

it will save an invese reachability map in the map_creator/Inv_map folder

After loading the inverse reachability map set the desired parameters. There are two parameters. Number of desired base locations and number of high scoring spheres from where the poses will be collected.

Set the desired output visualization method.(The robot model visualization is still in development. Coming Soon)
```

When everything is set up, press the Find Base button. It will show the base locations.

If you want to see the union map, press the show union map button.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,19 @@
#include <Eigen/Eigen>
#include <eigen_conversions/eigen_msg.h>

#include<moveit/move_group_interface/move_group.h>
#include<moveit/robot_state/robot_state.h>

#include<moveit/robot_model_loader/robot_model_loader.h>
#include<moveit/robot_model/robot_model.h>
#include<moveit/robot_model/joint_model_group.h>
#include<moveit/robot_model/link_model.h>
#if ROS_VERSION_MINIMUM(1,12,0)
#include <moveit/move_group_interface/move_group_interface.h>
typedef moveit::planning_interface::MoveGroupInterface MoveGroupInterface;
#else
#include <moveit/move_group_interface/move_group.h>
typedef moveit::planning_interface::MoveGroup MoveGroupInterface;
#endif


typedef std::multimap<std::vector<double>,geometry_msgs::Pose> BasePoseJoint;
Expand Down Expand Up @@ -52,7 +58,7 @@ class CreateMarker{

std::string group_name_;
ros::AsyncSpinner spinner;
boost::scoped_ptr<moveit::planning_interface::MoveGroup> group_;
boost::scoped_ptr<MoveGroupInterface> group_;
std::string parent_link;
moveit::core::RobotModelConstPtr robot_model_; //Robot model const pointer
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,14 @@
#include<base_placement_plugin/create_marker.h>

#include<moveit/planning_scene_monitor/planning_scene_monitor.h>
#include<moveit/move_group_interface/move_group.h>
#include<moveit/robot_model_loader/robot_model_loader.h>
#if ROS_VERSION_MINIMUM(1,12,0)
#include <moveit/move_group_interface/move_group_interface.h>
typedef moveit::planning_interface::MoveGroupInterface MoveGroupInterface;
#else
#include <moveit/move_group_interface/move_group.h>
typedef moveit::planning_interface::MoveGroup MoveGroupInterface;
#endif
#include<moveit/robot_model/robot_model.h>
#include<moveit/robot_model/joint_model_group.h>
#include<moveit/robot_state/robot_state.h>
Expand Down
2 changes: 1 addition & 1 deletion base_placement_plugin/plugin.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<library path="lib/libbase_placement_plugin">
<class name="base_placement_plugin/Base Placement Plug-in"
type="base_placement_plugin::AddWayPoint"
base_class_type="rviz::Panel">
base_class_type="rviz::Panel"/>
<description>
Tool for visualizing base placement methods
</description>
Expand Down
2 changes: 1 addition & 1 deletion base_placement_plugin/src/create_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ double unifRand()
CreateMarker::CreateMarker(std::string group_name) : spinner(1), group_name_(group_name)
{
spinner.start();
group_.reset(new moveit::planning_interface::MoveGroup(group_name_));
group_.reset(new MoveGroupInterface(group_name_));
//ROS_INFO_STREAM("Selected planning group: "<< group_->getName());
robot_model_ = group_->getRobotModel();
}
Expand Down
4 changes: 2 additions & 2 deletions base_placement_plugin/src/widgets/base_placement_widget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

#include <map_creator/hdf5_dataset.h>

#include <H5Cpp.h>
#include <hdf5.h>
#include <hdf5/serial/H5Cpp.h>
#include <hdf5/serial/hdf5.h>

namespace base_placement_plugin
{
Expand Down
13 changes: 7 additions & 6 deletions map_creator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,16 @@ find_package(catkin REQUIRED COMPONENTS
)

find_package(octomap REQUIRED)
find_package(HDF5 REQUIRED)
find_package(MPI REQUIRED)

add_message_files(
FILES
capShape.msg
capability.msg
WsSphere.msg
WorkSpace.msg

)

generate_messages(
Expand All @@ -41,23 +43,22 @@ catkin_package(
kinematics
hdf5_dataset
roscpp
CATKIN_DEPENDS message_runtime
CATKIN_DEPENDS message_runtime
)

include_directories(include ${catkin_INCLUDE_DIRS} ${OCTOMAP_INCLUDE_DIRS} ${HDF5_INCLUDE_DIR} ${PCL_INCLUDE_DIR})
include_directories(include ${catkin_INCLUDE_DIRS} ${OCTOMAP_INCLUDE_DIRS} ${HDF5_INCLUDE_DIRS} ${PCL_INCLUDE_DIR} ${MPI_CXX_INCLUDE_DIRS})

add_library(sphere_discretization src/sphere_discretization.cpp)
add_library(kinematics src/kinematics.cpp )
add_library(hdf5_dataset src/hdf5_dataset.cpp)

target_link_libraries(sphere_discretization ${catkin_LIBRARIES} ${OCTOMAP_LIBRARIES} ${PCL_LIBRARY_DIRS})
target_link_libraries(kinematics ${catkin_LIBRARIES} -llapack)
target_link_libraries(hdf5_dataset ${catkin_LIBRARIES} -lhdf5 -lhdf5_cpp)
target_link_libraries(hdf5_dataset ${catkin_LIBRARIES} ${HDF5_LIBRARIES} ${MPI_CXX_LIBRARIES})

install(TARGETS sphere_discretization kinematics hdf5_dataset
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}

)

install(DIRECTORY include/${PROJECT_NAME}/
Expand Down
41 changes: 27 additions & 14 deletions map_creator/README.md
Original file line number Diff line number Diff line change
@@ -1,40 +1,53 @@
## Map Creator
====
***All the Inverse Kinematics solutions for Reuleaux is generated by ikfast. The generated solutions from ikfast for the desired robot should be linked with the header files of Reuleaux. Please refer to the [http://wiki.ros.org/reuleaux] (http://wiki.ros.org/reuleaux) page for the process of generating ikfast solution for your robot and linking the ikfast solution to Reuleaux. The default robot provided in the package is motorman_mh5. You can easily import your robot by the instructions.***

Reuleaux map_creator pacakge creates three types of maps. (You don’t have to create all the maps, it is per your needs):
###1. Reachability map
The Reachability map describes the reachability of a given robot model by discretizing its environment, creating poses in the environment and calculating valid IK solutions for the poses. The poses which are reachable by robot are associated with discretized spheres. The reachability of each sphere in the environment are parameterized, by a Reachability index. The output is saved as an hdf5 file (link for hdf5 file) which has details about all the reachable poses and discretized spheres. There are mainly two user arguments:

a) Resolution parameter: The first step of the map generation process is discretization of the environment by voxelization. The resolution determines how much small the boxes would be. The smaller voxels, the higher the number of poses per spheres. (**Believe me, it grows exponentially. Please do not try to go too low with the resolution. The safe threshold is 0.05. Less than that, can take hours, or your system may stop responding**). If the user does not provide any resolution, the default resolution is 0.08

b) Map filename: The second argument decides the output filename. If the user does not provide an ouput filename, it will automatically decide an ugly map name with the robot name and provided resolution.
***All the Inverse Kinematics solutions for Reuleaux is generated by ikfast. The generated solutions from ikfast for the desired robot should be linked with the header files of Reuleaux. Please refer to the [http://wiki.ros.org/reuleaux](http://wiki.ros.org/reuleaux) page for the process of generating ikfast solution for your robot and linking the ikfast solution to Reuleaux. The default robot provided in the package is motorman_mh5. You can easily import your robot by the instructions.***

Reuleaux map_creator package creates three types of maps. (You don’t have to create all the maps, it is per your needs):

### 1. Reachability map

The Reachability map describes the reachability of a given robot model by discretizing its environment, creating poses in the environment and calculating valid IK solutions for the poses. The poses which are reachable by robot are associated with discretized spheres. The reachability of each sphere in the environment are parameterized, by a Reachability index. The output is saved as a hdf5 file (link for hdf5 file) which has details about all the reachable poses and discretized spheres. There are mainly two user arguments:

1. Resolution parameter: The first step of the map generation process is discretization of the environment by voxelization. The resolution determines how much small the boxes would be. The smaller voxels, the higher the number of poses per spheres. (**Believe me, it grows exponentially. Please do not try to go too low with the resolution. The safe threshold is 0.05. Less than that, can take hours, or your system may stop responding**). If the user does not provide any resolution, the default resolution is 0.08

2. Map filename: The second argument decides the output filename. If the user does not provide an ouput filename, it will automatically decide an ugly map name with the robot name and provided resolution.
To create a reachability map, run:

```
rosrun map_creator create_reachability_map
```

with arguments:

rosrun map_creator create_reachability_map funny_robot.h5 0.05

When the process finishes, the output reachability map will be stored in map_creator/maps folder. If you do not have the existing maps folder, do not worry. It will create a map folder in the map_creator package and store the output there.
```
rosrun map_creator create_reachability_map 0.05 funny_robot.h5
```

When the process finishes, the output reachability map will be stored in map_creator/maps folder. If you do not have the existing map's folder, do not worry. It will create a map folder in the map_creator package and store the output there.

###2. Capability Map (optional)
### 2. Capability Map (optional)
Capability map is an extension of reachability map (I guess you have already done that, otherwise please create a reachability map first), where the outer spheres of the reachability map, is set as cones. So the reachability limit of the robot is well visualized. All the outer spheres are decided for a principal axes and iterates over different values for opening angles for cones. The suitable opening angle that correctly accumulates all the poses on that sphere, is picked up
(** Until we found out some very useful algorithm for capability map, the process may take several hours based on resolution)
The process is same as creating reachability map:

```
rosrun map_creator create_capability_map
```

The ouput map file will also be stored in map_creator/maps folder.


###3. Inverse Reachability Map
### 3. Inverse Reachability Map
The purpose of Inverse Reachability map is to find suitable base positions for a robot with given task poses. To know how to find suitable bases, please refer to (base_placement plugin page)
The inverse reachability map is a general inverse transformation of all the reachable poses of the reachability map of the robot. The user have to provide the reachability map as an argument. The desired name of the ouput file can also be provided. If no output file name is provided, the system will automatically generate a map file with the robot name and resolution provided in the reachability map. To create an inverse reachability map:
The inverse reachability map is a general inverse transformation of all the reachable poses of the reachability map of the robot. The user have to provide the reachability map as an argument. The desired name of the output file can also be provided. If no output file name is provided, the system will automatically generate a map file with the robot name and resolution provided in the reachability map. To create an inverse reachability map:

```
rosrun map_creator create_inverse_reachability_map motoman_mh5_r0.08_reachability.h5
```

(provided reachability map is of motoman_mh5 robot and resolution is 0.08). The outout inverse reachability map will be stored in map_creator/Inv_map folder unless specified otherwise.
(provided reachability map is of motoman_mh5 robot and resolution is 0.08). The output inverse reachability map will be stored in map_creator/Inv_map folder unless specified otherwise.

(Congratulations. You have now also created the inverse reachability map which is the key element for finding bases. Now it is the time to see the result of all the hard work. Let’s move to the [visualization] (https://github.com/ros-industrial-consortium/reuleaux/tree/master/workspace_visualization) page)
(Congratulations. You have now also created the inverse reachability map which is the key element for finding bases. Now it is the time to see the result of all the hard work. Let’s move to the [visualization](../workspace_visualization/README.md) page)
4 changes: 2 additions & 2 deletions map_creator/include/map_creator/hdf5_dataset.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef HDF5_DATASET_H
#define HDF5_DATASET_H
#include "H5Cpp.h"
#include <hdf5.h>
#include <hdf5/serial/H5Cpp.h>
#include <hdf5/serial/hdf5.h>
#include <iostream>
#include <ros/ros.h>

Expand Down
Loading