$search
Configuration of actions that need to actuate parts of the robot. More...
#include <move_arm_setup.h>
Public Member Functions | |
bool | configure (void) |
MoveArmSetup (void) | |
virtual | ~MoveArmSetup (void) |
Protected Member Functions | |
bool | getControlJointNames (std::vector< std::string > &joint_names) |
Protected Attributes | |
planning_environment::CollisionModels * | collision_models_ |
std::string | group_ |
std::vector< std::string > | groupJointNames_ |
ros::NodeHandle | nodeHandle_ |
planning_environment::PlanningMonitor * | planning_monitor_ |
ros::NodeHandle | root_handle_ |
tf::TransformListener | tf_ |
Private Attributes | |
bool | use_collision_map_ |
Friends | |
class | MoveArm |
class | MoveArmMonitor |
class | TeleopArm |
Configuration of actions that need to actuate parts of the robot.
Definition at line 70 of file move_arm_setup.h.
move_arm::MoveArmSetup::MoveArmSetup | ( | void | ) | [inline] |
Definition at line 78 of file move_arm_setup.h.
virtual move_arm::MoveArmSetup::~MoveArmSetup | ( | void | ) | [inline, virtual] |
Definition at line 84 of file move_arm_setup.h.
bool move_arm::MoveArmSetup::configure | ( | void | ) |
bool move_arm::MoveArmSetup::getControlJointNames | ( | std::vector< std::string > & | joint_names | ) | [protected] |
friend class MoveArm [friend] |
Definition at line 72 of file move_arm_setup.h.
friend class MoveArmMonitor [friend] |
Definition at line 73 of file move_arm_setup.h.
friend class TeleopArm [friend] |
Definition at line 74 of file move_arm_setup.h.
Definition at line 101 of file move_arm_setup.h.
std::string move_arm::MoveArmSetup::group_ [protected] |
Definition at line 104 of file move_arm_setup.h.
std::vector<std::string> move_arm::MoveArmSetup::groupJointNames_ [protected] |
Definition at line 105 of file move_arm_setup.h.
ros::NodeHandle move_arm::MoveArmSetup::nodeHandle_ [protected] |
Definition at line 99 of file move_arm_setup.h.
Definition at line 102 of file move_arm_setup.h.
ros::NodeHandle move_arm::MoveArmSetup::root_handle_ [protected] |
Definition at line 99 of file move_arm_setup.h.
tf::TransformListener move_arm::MoveArmSetup::tf_ [protected] |
Definition at line 100 of file move_arm_setup.h.
bool move_arm::MoveArmSetup::use_collision_map_ [private] |
Definition at line 108 of file move_arm_setup.h.