This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) robot arms.
More...
#include <follow_joint_trajectory.h>
This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) robot arms.
Definition at line 65 of file follow_joint_trajectory.h.
robot_controllers::FollowJointTrajectoryController::FollowJointTrajectoryController |
( |
| ) |
|
virtual robot_controllers::FollowJointTrajectoryController::~FollowJointTrajectoryController |
( |
| ) |
|
|
inlinevirtual |
void robot_controllers::FollowJointTrajectoryController::executeCb |
( |
const control_msgs::FollowJointTrajectoryGoalConstPtr & |
goal | ) |
|
|
private |
std::vector< std::string > robot_controllers::FollowJointTrajectoryController::getClaimedNames |
( |
| ) |
|
|
virtual |
std::vector< std::string > robot_controllers::FollowJointTrajectoryController::getCommandedNames |
( |
| ) |
|
|
virtual |
TrajectoryPoint robot_controllers::FollowJointTrajectoryController::getPointFromCurrent |
( |
bool |
incl_vel, |
|
|
bool |
incl_acc, |
|
|
bool |
zero_vel |
|
) |
| |
|
private |
virtual std::string robot_controllers::FollowJointTrajectoryController::getType |
( |
| ) |
|
|
inlinevirtual |
Initialize the controller and any required data structures.
- Parameters
-
nh | Node handle for this controller. |
manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
- Returns
- 0 if succesfully configured, negative values are error codes.
Reimplemented from robot_controllers::Controller.
Definition at line 53 of file follow_joint_trajectory.cpp.
bool robot_controllers::FollowJointTrajectoryController::reset |
( |
| ) |
|
|
virtual |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
- Returns
- True if successfully reset, false otherwise.
Implements robot_controllers::Controller.
Definition at line 177 of file follow_joint_trajectory.cpp.
bool robot_controllers::FollowJointTrajectoryController::start |
( |
| ) |
|
|
virtual |
bool robot_controllers::FollowJointTrajectoryController::stop |
( |
bool |
force | ) |
|
|
virtual |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
- Parameters
-
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
- Returns
- True if successfully stopped, false otherwise.
Implements robot_controllers::Controller.
Definition at line 155 of file follow_joint_trajectory.cpp.
void robot_controllers::FollowJointTrajectoryController::update |
( |
const ros::Time & |
now, |
|
|
const ros::Duration & |
dt |
|
) |
| |
|
virtual |
std::vector<bool> robot_controllers::FollowJointTrajectoryController::continuous_ |
|
private |
control_msgs::FollowJointTrajectoryFeedback robot_controllers::FollowJointTrajectoryController::feedback_ |
|
private |
ros::Time robot_controllers::FollowJointTrajectoryController::goal_time |
|
private |
double robot_controllers::FollowJointTrajectoryController::goal_time_tolerance_ |
|
private |
TrajectoryPoint robot_controllers::FollowJointTrajectoryController::goal_tolerance_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::has_goal_tolerance_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::has_path_tolerance_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::initialized_ |
|
private |
std::vector<std::string> robot_controllers::FollowJointTrajectoryController::joint_names_ |
|
private |
std::vector<JointHandlePtr> robot_controllers::FollowJointTrajectoryController::joints_ |
|
private |
TrajectoryPoint robot_controllers::FollowJointTrajectoryController::last_sample_ |
|
private |
TrajectoryPoint robot_controllers::FollowJointTrajectoryController::path_tolerance_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::preempted_ |
|
private |
boost::mutex robot_controllers::FollowJointTrajectoryController::sampler_mutex_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::stop_on_path_violation_ |
|
private |
bool robot_controllers::FollowJointTrajectoryController::stop_with_action_ |
|
private |
The documentation for this class was generated from the following files: