Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
play_motion::PlayMotion Class Reference

#include <play_motion.h>

List of all members.

Classes

class  Goal

Public Types

typedef boost::shared_ptr< GoalGoalHandle

Public Member Functions

 PlayMotion (ros::NodeHandle &nh)
bool run (const std::string &motion_name, bool skip_planning, GoalHandle &gh, const Callback &cb)
 Send motion goal request.

Private Types

typedef boost::shared_ptr
< ApproachPlanner
ApproachPlannerPtr
typedef boost::function< void(const
GoalHandle &)> 
Callback
typedef std::list
< MoveJointGroupPtr
ControllerList
typedef boost::shared_ptr
< MoveJointGroup
MoveJointGroupPtr

Private Member Functions

bool getGroupTraj (MoveJointGroupPtr move_joint_group, const JointNames &motion_joints, const Trajectory &motion_points, Trajectory &traj_group)
ControllerList getMotionControllers (const JointNames &motion_joints)
 Populate a list of controllers that span the motion joints.
void getMotionJoints (const std::string &motion_name, JointNames &motion_joints)
void getMotionPoints (const std::string &motion_name, Trajectory &motion_points)
void jointStateCb (const sensor_msgs::JointStatePtr &msg)
void updateControllersCb (const ControllerUpdater::ControllerStates &states, const ControllerUpdater::ControllerJoints &joints)

Private Attributes

ApproachPlannerPtr approach_planner_
ControllerUpdater ctrlr_updater_
std::map< std::string, double > joint_states_
ros::Subscriber joint_states_sub_
ControllerList move_joint_groups_
ros::NodeHandle nh_

Detailed Description

Move robot joints to a given pose. Poses are specified in the parameter server, and are identified by name.

Definition at line 78 of file play_motion.h.


Member Typedef Documentation

typedef boost::shared_ptr<ApproachPlanner> play_motion::PlayMotion::ApproachPlannerPtr [private]

Definition at line 87 of file play_motion.h.

typedef boost::function<void(const GoalHandle&)> play_motion::PlayMotion::Callback [private]

Definition at line 86 of file play_motion.h.

Definition at line 85 of file play_motion.h.

typedef boost::shared_ptr<Goal> play_motion::PlayMotion::GoalHandle

Definition at line 81 of file play_motion.h.

typedef boost::shared_ptr<MoveJointGroup> play_motion::PlayMotion::MoveJointGroupPtr [private]

Definition at line 84 of file play_motion.h.


Constructor & Destructor Documentation

Definition at line 133 of file play_motion.cpp.


Member Function Documentation

bool play_motion::PlayMotion::getGroupTraj ( MoveJointGroupPtr  move_joint_group,
const JointNames motion_joints,
const Trajectory motion_points,
Trajectory traj_group 
) [private]

Definition at line 189 of file play_motion.cpp.

Populate a list of controllers that span the motion joints.

In the general case, the controllers will span more than the motion joints, but never less. This method also validates that the controllers are not busy executing another goal.

Parameters:
motion_jointsList of motion joints.
Returns:
A list of controllers that span (at least) all the motion joints.
Exceptions:
PMExceptionif no controllers spanning the motion joints were found, or if some of them are busy.

Definition at line 287 of file play_motion.cpp.

void play_motion::PlayMotion::getMotionJoints ( const std::string &  motion_name,
JointNames motion_joints 
) [private]

Definition at line 247 of file play_motion.cpp.

void play_motion::PlayMotion::getMotionPoints ( const std::string &  motion_name,
Trajectory motion_points 
) [private]

Definition at line 267 of file play_motion.cpp.

void play_motion::PlayMotion::jointStateCb ( const sensor_msgs::JointStatePtr &  msg) [private]

Definition at line 182 of file play_motion.cpp.

bool play_motion::PlayMotion::run ( const std::string &  motion_name,
bool  skip_planning,
GoalHandle gh,
const Callback cb 
)

Send motion goal request.

Parameters:
motion_nameName of motion to execute.
skip_planningSkip motion planning for computing the approach trajectory.
[out]goal_idcontains the goal ID if function returns true

Definition at line 318 of file play_motion.cpp.

Definition at line 168 of file play_motion.cpp.


Member Data Documentation

Definition at line 146 of file play_motion.h.

Definition at line 145 of file play_motion.h.

std::map<std::string, double> play_motion::PlayMotion::joint_states_ [private]

Definition at line 143 of file play_motion.h.

Definition at line 144 of file play_motion.h.

Definition at line 142 of file play_motion.h.

Definition at line 141 of file play_motion.h.


The documentation for this class was generated from the following files:


play_motion
Author(s): Paul Mathieu , Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:26:22