Skip to content

Commit

Permalink
Fix warnings about Eigen and deprecated classes (moveit#38)
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman authored and v4hn committed Oct 25, 2016
1 parent 094f104 commit 9bc4bc4
Show file tree
Hide file tree
Showing 4 changed files with 67 additions and 58 deletions.
15 changes: 12 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,21 @@
cmake_minimum_required(VERSION 2.8.3)
project(moveit_tutorials)

add_compile_options(-std=c++11)

find_package(Eigen3 REQUIRED)

# Eigen 3.2 (Wily) only provides EIGEN3_INCLUDE_DIR, not EIGEN3_INCLUDE_DIRS
if(NOT EIGEN3_INCLUDE_DIRS)
set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
endif()

find_package(catkin REQUIRED
COMPONENTS
moveit_core
moveit_ros_planning
moveit_ros_planning_interface
pluginlib
cmake_modules
geometric_shapes
)

Expand All @@ -18,14 +26,15 @@ catkin_package(
moveit_core
moveit_ros_planning_interface
interactive_markers
DEPENDS
EIGEN3
)
find_package(Eigen REQUIRED)

###########
## Build ##
###########

include_directories(SYSTEM ${Boost_INCLUDE_DIR} ${EIGEN_INCLUDE_DIRS})
include_directories(SYSTEM ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS})
include_directories(${catkin_INCLUDE_DIRS})
link_directories(${catkin_LIBRARY_DIRS})

Expand Down
12 changes: 6 additions & 6 deletions doc/pr2_tutorials/pick_place/src/pick_place_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

// MoveIt!
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/move_group_interface/move_group.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <geometric_shapes/solid_primitive_dims.h>

static const std::string ROBOT_DESCRIPTION="robot_description";
Expand Down Expand Up @@ -82,7 +82,7 @@ void closedGripper(trajectory_msgs::JointTrajectory& posture){
}


void pick(moveit::planning_interface::MoveGroup &group)
void pick(moveit::planning_interface::MoveGroupInterface &group)
{
std::vector<moveit_msgs::Grasp> grasps;

Expand Down Expand Up @@ -117,7 +117,7 @@ void pick(moveit::planning_interface::MoveGroup &group)
group.pick("part", grasps);
}

void place(moveit::planning_interface::MoveGroup &group)
void place(moveit::planning_interface::MoveGroupInterface &group)
{
std::vector<moveit_msgs::PlaceLocation> loc;

Expand Down Expand Up @@ -180,7 +180,7 @@ int main(int argc, char **argv)

ros::WallDuration(1.0).sleep();

moveit::planning_interface::MoveGroup group("right_arm");
moveit::planning_interface::MoveGroupInterface group("right_arm");
group.setPlanningTime(45.0);

moveit_msgs::CollisionObject co;
Expand Down Expand Up @@ -229,11 +229,11 @@ int main(int argc, char **argv)
co.id = "part";
co.operation = moveit_msgs::CollisionObject::REMOVE;
pub_co.publish(co);

moveit_msgs::AttachedCollisionObject aco;
aco.object = co;
pub_aco.publish(aco);

co.operation = moveit_msgs::CollisionObject::ADD;
co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.15;
co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
Expand Down
96 changes: 48 additions & 48 deletions doc/pr2_tutorials/planning/src/move_group_interface_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

/* Author: Sachin Chitta */

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

#include <moveit_msgs/DisplayRobotState.h>
Expand All @@ -46,27 +46,27 @@
int main(int argc, char **argv)
{
ros::init(argc, argv, "move_group_interface_tutorial");
ros::NodeHandle node_handle;
ros::NodeHandle node_handle;
ros::AsyncSpinner spinner(1);
spinner.start();


/* This sleep is ONLY to allow Rviz to come up */
sleep(20.0);

// BEGIN_TUTORIAL
//
//
// Setup
// ^^^^^
//
// The :move_group_interface:`MoveGroup` class can be easily
//
// The :move_group_interface:`MoveGroup` class can be easily
// setup using just the name
// of the group you would like to control and plan for.
moveit::planning_interface::MoveGroup group("right_arm");
moveit::planning_interface::MoveGroupInterface group("right_arm");

// We will use the :planning_scene_interface:`PlanningSceneInterface`
// class to deal directly with the world.
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;

// (Optional) Create a publisher for visualizing plans in Rviz.
ros::Publisher display_publisher = node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true);
Expand All @@ -77,13 +77,13 @@ int main(int argc, char **argv)
//
// We can print the name of the reference frame for this robot.
ROS_INFO("Reference frame: %s", group.getPlanningFrame().c_str());

// We can also print the name of the end-effector link for this group.
ROS_INFO("Reference frame: %s", group.getEndEffectorLink().c_str());

// Planning to a Pose goal
// ^^^^^^^^^^^^^^^^^^^^^^^
// We can plan a motion for this group to a desired pose for the
// We can plan a motion for this group to a desired pose for the
// end-effector.
geometry_msgs::Pose target_pose1;
target_pose1.orientation.w = 1.0;
Expand All @@ -95,12 +95,12 @@ int main(int argc, char **argv)

// Now, we call the planner to compute the plan
// and visualize it.
// Note that we are just planning, not asking move_group
// Note that we are just planning, not asking move_group
// to actually move the robot.
moveit::planning_interface::MoveGroup::Plan my_plan;
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
bool success = group.plan(my_plan);

ROS_INFO("Visualizing plan 1 (pose goal) %s",success?"":"FAILED");
ROS_INFO("Visualizing plan 1 (pose goal) %s",success?"":"FAILED");
/* Sleep to give Rviz time to visualize the plan. */
sleep(5.0);

Expand All @@ -112,29 +112,29 @@ int main(int argc, char **argv)
// want to visualize a previously created plan.
if (1)
{
ROS_INFO("Visualizing plan 1 (again)");
ROS_INFO("Visualizing plan 1 (again)");
display_trajectory.trajectory_start = my_plan.start_state_;
display_trajectory.trajectory.push_back(my_plan.trajectory_);
display_publisher.publish(display_trajectory);
/* Sleep to give Rviz time to visualize the plan. */
sleep(5.0);
}

// Moving to a pose goal
// ^^^^^^^^^^^^^^^^^^^^^
//
// Moving to a pose goal is similar to the step above
// except we now use the move() function. Note that
// the pose goal we had set earlier is still active
// the pose goal we had set earlier is still active
// and so the robot will try to move to that goal. We will
// not use that function in this tutorial since it is
// not use that function in this tutorial since it is
// a blocking function and requires a controller to be active
// and report success on execution of a trajectory.

/* Uncomment below line when working with a real robot*/
/* group.move() */

// Planning to a joint-space goal
// Planning to a joint-space goal
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
//
// Let's set a joint space goal and move towards it. This will replace the
Expand All @@ -143,10 +143,10 @@ int main(int argc, char **argv)
// First get the current set of joint values for the group.
std::vector<double> group_variable_values;
group.getCurrentState()->copyJointGroupPositions(group.getCurrentState()->getRobotModel()->getJointModelGroup(group.getName()), group_variable_values);

// Now, let's modify one of the joints, plan to the new joint
// space goal and visualize the plan.
group_variable_values[0] = -1.0;
group_variable_values[0] = -1.0;
group.setJointValueTarget(group_variable_values);
success = group.plan(my_plan);

Expand All @@ -160,24 +160,24 @@ int main(int argc, char **argv)
// Path constraints can easily be specified for a link on the robot.
// Let's specify a path constraint and a pose goal for our group.
// First define the path constraint.
moveit_msgs::OrientationConstraint ocm;
ocm.link_name = "r_wrist_roll_link";
moveit_msgs::OrientationConstraint ocm;
ocm.link_name = "r_wrist_roll_link";
ocm.header.frame_id = "base_link";
ocm.orientation.w = 1.0;
ocm.absolute_x_axis_tolerance = 0.1;
ocm.absolute_y_axis_tolerance = 0.1;
ocm.absolute_z_axis_tolerance = 0.1;
ocm.weight = 1.0;

// Now, set it as the path constraint for the group.
moveit_msgs::Constraints test_constraints;
test_constraints.orientation_constraints.push_back(ocm);
test_constraints.orientation_constraints.push_back(ocm);
group.setPathConstraints(test_constraints);

// We will reuse the old goal that we had and plan to it.
// Note that this will only work if the current state already
// Note that this will only work if the current state already
// satisfies the path constraints. So, we need to set the start
// state to a new pose.
// state to a new pose.
robot_state::RobotState start_state(*group.getCurrentState());
geometry_msgs::Pose start_pose2;
start_pose2.orientation.w = 1.0;
Expand All @@ -188,8 +188,8 @@ int main(int argc, char **argv)
start_state.getJointModelGroup(group.getName());
start_state.setFromIK(joint_model_group, start_pose2);
group.setStartState(start_state);
// Now we will plan to the earlier pose target from the new

// Now we will plan to the earlier pose target from the new
// start state that we have just created.
group.setPoseTarget(target_pose1);
success = group.plan(my_plan);
Expand All @@ -203,8 +203,8 @@ int main(int argc, char **argv)

// Cartesian Paths
// ^^^^^^^^^^^^^^^
// You can plan a cartesian path directly by specifying a list of waypoints
// for the end-effector to go through. Note that we are starting
// You can plan a cartesian path directly by specifying a list of waypoints
// for the end-effector to go through. Note that we are starting
// from the new start state above. The initial pose (start state) does not
// need to be added to the waypoint list.
std::vector<geometry_msgs::Pose> waypoints;
Expand Down Expand Up @@ -233,7 +233,7 @@ int main(int argc, char **argv)
trajectory);

ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",
fraction * 100.0);
fraction * 100.0);
/* Sleep to give Rviz time to visualize the plan. */
sleep(15.0);

Expand Down Expand Up @@ -266,13 +266,13 @@ int main(int argc, char **argv)
collision_object.primitive_poses.push_back(box_pose);
collision_object.operation = collision_object.ADD;

std::vector<moveit_msgs::CollisionObject> collision_objects;
collision_objects.push_back(collision_object);
std::vector<moveit_msgs::CollisionObject> collision_objects;
collision_objects.push_back(collision_object);

// Now, let's add the collision object into the world
ROS_INFO("Add an object into the world");
ROS_INFO("Add an object into the world");
planning_scene_interface.addCollisionObjects(collision_objects);

/* Sleep so we have time to see the object in RViz */
sleep(2.0);

Expand All @@ -291,37 +291,37 @@ int main(int argc, char **argv)
success?"":"FAILED");
/* Sleep to give Rviz time to visualize the plan. */
sleep(10.0);


// Now, let's attach the collision object to the robot.
ROS_INFO("Attach the object to the robot");
group.attachObject(collision_object.id);
ROS_INFO("Attach the object to the robot");
group.attachObject(collision_object.id);
/* Sleep to give Rviz time to show the object attached (different color). */
sleep(4.0);


// Now, let's detach the collision object from the robot.
ROS_INFO("Detach the object from the robot");
group.detachObject(collision_object.id);
ROS_INFO("Detach the object from the robot");
group.detachObject(collision_object.id);
/* Sleep to give Rviz time to show the object detached. */
sleep(4.0);


// Now, let's remove the collision object from the world.
ROS_INFO("Remove the object from the world");
ROS_INFO("Remove the object from the world");
std::vector<std::string> object_ids;
object_ids.push_back(collision_object.id);
object_ids.push_back(collision_object.id);
planning_scene_interface.removeCollisionObjects(object_ids);
/* Sleep to give Rviz time to show the object is no longer there. */
sleep(4.0);


// Dual-arm pose goals
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
// First define a new group for addressing the two arms. Then define
// two separate pose goals, one for each end-effector. Note that
// First define a new group for addressing the two arms. Then define
// two separate pose goals, one for each end-effector. Note that
// we are reusing the goal for the right arm above
moveit::planning_interface::MoveGroup two_arms_group("arms");
moveit::planning_interface::MoveGroupInterface two_arms_group("arms");

two_arms_group.setPoseTarget(target_pose1, "r_wrist_roll_link");

Expand All @@ -334,12 +334,12 @@ int main(int argc, char **argv)
two_arms_group.setPoseTarget(target_pose2, "l_wrist_roll_link");

// Now, we can plan and visualize
moveit::planning_interface::MoveGroup::Plan two_arms_plan;
moveit::planning_interface::MoveGroupInterface::Plan two_arms_plan;
two_arms_group.plan(two_arms_plan);
sleep(4.0);

// END_TUTORIAL

ros::shutdown();
ros::shutdown();
return 0;
}
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>pluginlib</build_depend>
<build_depend>eigen</build_depend>
<build_depend>moveit_core</build_depend>
<build_depend>moveit_ros_planning_interface</build_depend>
<build_depend>moveit_ros_perception</build_depend>
<build_depend>interactive_markers</build_depend>
<build_depend>cmake_modules</build_depend>
<build_depend>geometric_shapes</build_depend>

<run_depend>pluginlib</run_depend>
Expand Down

0 comments on commit 9bc4bc4

Please sign in to comment.