#include <play_motion.h>
Classes | |
class | Goal |
Public Types | |
typedef boost::shared_ptr< Goal > | GoalHandle |
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_ |
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.
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.
typedef std::list<MoveJointGroupPtr> play_motion::PlayMotion::ControllerList [private] |
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.
Definition at line 133 of file play_motion.cpp.
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.
ControllerList play_motion::PlayMotion::getMotionControllers | ( | const JointNames & | motion_joints | ) | [private] |
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.
motion_joints | List of motion joints. |
PMException | if 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.
motion_name | Name of motion to execute. | |
skip_planning | Skip motion planning for computing the approach trajectory. | |
[out] | goal_id | contains the goal ID if function returns true |
Definition at line 318 of file play_motion.cpp.
void play_motion::PlayMotion::updateControllersCb | ( | const ControllerUpdater::ControllerStates & | states, |
const ControllerUpdater::ControllerJoints & | joints | ||
) | [private] |
Definition at line 168 of file play_motion.cpp.
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.
ros::NodeHandle play_motion::PlayMotion::nh_ [private] |
Definition at line 141 of file play_motion.h.