#include <move_joint_group.h>
Public Member Functions | |
void | cancel () |
Cancel the current goal. | |
const JointNames & | getJointNames () const |
Returns the list of associated joints. | |
const std::string & | getName () const |
Returns the name that was used when creating the MoveJointGroup. | |
actionlib::SimpleClientGoalState | getState () |
Returns the action client state. | |
bool | isControllingJoint (const std::string &joint_name) |
Returns true if the specified joint is controlled by the controller. joint_name Joint name. | |
bool | isIdle () const |
Returns true if the MoveJointGroup is ready to accept a new goal. | |
MoveJointGroup (const std::string &controller_name, const JointNames &joint_names) | |
bool | sendGoal (const std::vector< TrajPoint > &traj) |
Send a trajectory goal to the associated controller. | |
void | setCallback (const Callback &cb) |
Register the callback to be called when the action is finished. | |
Private Types | |
typedef actionlib::SimpleActionClient < control_msgs::FollowJointTrajectoryAction > | ActionClient |
typedef control_msgs::FollowJointTrajectoryGoal | ActionGoal |
typedef control_msgs::FollowJointTrajectoryResult | ActionResult |
typedef boost::shared_ptr < const ActionResult > | ActionResultPtr |
typedef boost::function< void(int)> | Callback |
Private Member Functions | |
void | alCallback () |
Private Attributes | |
Callback | active_cb_ |
Call this when we are called back from the controller. | |
bool | busy_ |
ActionClient | client_ |
Action client used to trigger motions. | |
ros::Timer | configure_timer_ |
To periodically check for controller actionlib server. | |
std::string | controller_name_ |
Controller name. XXX: is this needed? | |
JointNames | joint_names_ |
Names of controller joints. | |
ros::NodeHandle | nh_ |
Default node handle. |
Move a joint group to a given pose. The pose will be reached within a specified duration with zero velocity.
Definition at line 55 of file move_joint_group.h.
typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> play_motion::MoveJointGroup::ActionClient [private] |
Definition at line 59 of file move_joint_group.h.
typedef control_msgs::FollowJointTrajectoryGoal play_motion::MoveJointGroup::ActionGoal [private] |
Definition at line 60 of file move_joint_group.h.
typedef control_msgs::FollowJointTrajectoryResult play_motion::MoveJointGroup::ActionResult [private] |
Definition at line 61 of file move_joint_group.h.
typedef boost::shared_ptr<const ActionResult> play_motion::MoveJointGroup::ActionResultPtr [private] |
Definition at line 62 of file move_joint_group.h.
typedef boost::function<void(int)> play_motion::MoveJointGroup::Callback [private] |
Definition at line 63 of file move_joint_group.h.
play_motion::MoveJointGroup::MoveJointGroup | ( | const std::string & | controller_name, |
const JointNames & | joint_names | ||
) |
Definition at line 47 of file move_joint_group.cpp.
void play_motion::MoveJointGroup::alCallback | ( | ) | [private] |
Definition at line 54 of file move_joint_group.cpp.
void play_motion::MoveJointGroup::cancel | ( | ) |
Cancel the current goal.
Definition at line 67 of file move_joint_group.cpp.
const JointNames & play_motion::MoveJointGroup::getJointNames | ( | ) | const |
Returns the list of associated joints.
Definition at line 78 of file move_joint_group.cpp.
const std::string & play_motion::MoveJointGroup::getName | ( | ) | const |
Returns the name that was used when creating the MoveJointGroup.
Definition at line 88 of file move_joint_group.cpp.
Returns the action client state.
Definition at line 83 of file move_joint_group.cpp.
bool play_motion::MoveJointGroup::isControllingJoint | ( | const std::string & | joint_name | ) |
Returns true if the specified joint is controlled by the controller. joint_name Joint name.
Definition at line 93 of file move_joint_group.cpp.
bool play_motion::MoveJointGroup::isIdle | ( | ) | const |
Returns true if the MoveJointGroup is ready to accept a new goal.
Definition at line 62 of file move_joint_group.cpp.
bool play_motion::MoveJointGroup::sendGoal | ( | const std::vector< TrajPoint > & | traj | ) |
Send a trajectory goal to the associated controller.
traj | The trajectory to send |
Definition at line 105 of file move_joint_group.cpp.
void play_motion::MoveJointGroup::setCallback | ( | const Callback & | cb | ) |
Register the callback to be called when the action is finished.
cb | The callback |
Definition at line 73 of file move_joint_group.cpp.
Call this when we are called back from the controller.
Definition at line 121 of file move_joint_group.h.
bool play_motion::MoveJointGroup::busy_ [private] |
Definition at line 116 of file move_joint_group.h.
Action client used to trigger motions.
Definition at line 120 of file move_joint_group.h.
To periodically check for controller actionlib server.
Definition at line 122 of file move_joint_group.h.
std::string play_motion::MoveJointGroup::controller_name_ [private] |
Controller name. XXX: is this needed?
Definition at line 118 of file move_joint_group.h.
Names of controller joints.
Definition at line 119 of file move_joint_group.h.
Default node handle.
Definition at line 117 of file move_joint_group.h.