#include <ros/ros.h>
#include <math.h>
#include <arm_navigation_msgs/GetStateValidity.h>
#include <interactive_markers/interactive_marker_server.h>
#include <interactive_markers/menu_handler.h>
#include <object_manipulator/tools/mechanism_interface.h>
#include <object_manipulator/tools/msg_helpers.h>
#include <object_manipulator/tools/arm_configurations.h>
#include <object_manipulator/tools/vector_tools.h>
#include <object_manipulator/tools/service_action_wrappers.h>
#include <std_srvs/Empty.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/server/simple_action_server.h>
#include <boost/thread.hpp>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <pr2_wrappers/gripper_controller.h>
#include <pr2_wrappers/torso_client.h>
#include <pr2_wrappers/base_client.h>
#include <pr2_wrappers/tuck_arms_client.h>
#include <pr2_wrappers/plugs_client.h>
#include <point_cloud_server/StoreCloudAction.h>
#include <pr2_object_manipulation_msgs/GetNavPoseAction.h>
#include <pr2_object_manipulation_msgs/GetGripperPoseAction.h>
#include <interactive_marker_helpers/interactive_marker_helpers.h>
#include <pr2_marker_control/cloud_handler.h>
#include <boost/thread/thread.hpp>
Go to the source code of this file.
Classes | |
struct | PR2MarkerControl::ControlState |
A struct to keep the state of the overall robot control. More... | |
struct | PR2MarkerControl::GripperState |
A struct to store the state of the gripper controls. More... | |
class | PR2MarkerControl |
A class for controlling the PR2 using interactive markers. More... |