Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
robot_controllers::FollowJointTrajectoryController Class Reference

This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) robot arms. More...

#include <follow_joint_trajectory.h>

Inheritance diagram for robot_controllers::FollowJointTrajectoryController:
Inheritance graph
[legend]

Public Member Functions

 FollowJointTrajectoryController ()
 
virtual std::vector< std::string > getClaimedNames ()
 Get the names of joints/controllers which this controller exclusively claims. More...
 
virtual std::vector< std::string > getCommandedNames ()
 Get the names of joints/controllers which this controller commands. More...
 
virtual std::string getType ()
 Get the type of this controller. More...
 
virtual int init (ros::NodeHandle &nh, ControllerManager *manager)
 Initialize the controller and any required data structures. More...
 
virtual bool reset ()
 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. More...
 
virtual bool start ()
 Attempt to start the controller. This should be called only by the ControllerManager instance. More...
 
virtual bool stop (bool force)
 Attempt to stop the controller. This should be called only by the ControllerManager instance. More...
 
virtual void update (const ros::Time &now, const ros::Duration &dt)
 This is the update loop for the controller. More...
 
virtual ~FollowJointTrajectoryController ()
 
- Public Member Functions inherited from robot_controllers::Controller
 Controller ()
 
std::string getName ()
 
virtual ~Controller ()
 
- Public Member Functions inherited from robot_controllers::Handle
 Handle ()
 
virtual ~Handle ()
 

Private Types

typedef actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > server_t
 

Private Member Functions

void executeCb (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
 Callback for goal. More...
 
TrajectoryPoint getPointFromCurrent (bool incl_vel, bool incl_acc, bool zero_vel)
 Get a trajectory point from the current position/velocity/acceleration. More...
 

Private Attributes

std::vector< bool > continuous_
 
control_msgs::FollowJointTrajectoryFeedback feedback_
 
ros::Time goal_time
 
double goal_time_tolerance_
 
TrajectoryPoint goal_tolerance_
 
bool has_goal_tolerance_
 
bool has_path_tolerance_
 
bool initialized_
 
std::vector< std::string > joint_names_
 
std::vector< JointHandlePtrjoints_
 
TrajectoryPoint last_sample_
 
ControllerManagermanager_
 
TrajectoryPoint path_tolerance_
 
bool preempted_
 
boost::shared_ptr< TrajectorySamplersampler_
 
boost::mutex sampler_mutex_
 
boost::shared_ptr< server_tserver_
 
bool stop_on_path_violation_
 
bool stop_with_action_
 

Detailed Description

This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) robot arms.

Definition at line 65 of file follow_joint_trajectory.h.

Member Typedef Documentation

typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> robot_controllers::FollowJointTrajectoryController::server_t
private

Definition at line 67 of file follow_joint_trajectory.h.

Constructor & Destructor Documentation

robot_controllers::FollowJointTrajectoryController::FollowJointTrajectoryController ( )

Definition at line 48 of file follow_joint_trajectory.cpp.

virtual robot_controllers::FollowJointTrajectoryController::~FollowJointTrajectoryController ( )
inlinevirtual

Definition at line 71 of file follow_joint_trajectory.h.

Member Function Documentation

void robot_controllers::FollowJointTrajectoryController::executeCb ( const control_msgs::FollowJointTrajectoryGoalConstPtr &  goal)
private

Callback for goal.

Definition at line 344 of file follow_joint_trajectory.cpp.

std::vector< std::string > robot_controllers::FollowJointTrajectoryController::getClaimedNames ( )
virtual

Get the names of joints/controllers which this controller exclusively claims.

Implements robot_controllers::Controller.

Definition at line 612 of file follow_joint_trajectory.cpp.

std::vector< std::string > robot_controllers::FollowJointTrajectoryController::getCommandedNames ( )
virtual

Get the names of joints/controllers which this controller commands.

Implements robot_controllers::Controller.

Definition at line 607 of file follow_joint_trajectory.cpp.

TrajectoryPoint robot_controllers::FollowJointTrajectoryController::getPointFromCurrent ( bool  incl_vel,
bool  incl_acc,
bool  zero_vel 
)
private

Get a trajectory point from the current position/velocity/acceleration.

Definition at line 572 of file follow_joint_trajectory.cpp.

virtual std::string robot_controllers::FollowJointTrajectoryController::getType ( )
inlinevirtual

Get the type of this controller.

Reimplemented from robot_controllers::Controller.

Definition at line 114 of file follow_joint_trajectory.h.

int robot_controllers::FollowJointTrajectoryController::init ( ros::NodeHandle nh,
ControllerManager manager 
)
virtual

Initialize the controller and any required data structures.

Parameters
nhNode handle for this controller.
managerThe 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

Attempt to start the controller. This should be called only by the ControllerManager instance.

Returns
True if successfully started, false otherwise.

Implements robot_controllers::Controller.

Definition at line 136 of file follow_joint_trajectory.cpp.

bool robot_controllers::FollowJointTrajectoryController::stop ( bool  force)
virtual

Attempt to stop the controller. This should be called only by the ControllerManager instance.

Parameters
forceShould 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

This is the update loop for the controller.

Parameters
timeThe system time.
dtThe timestep since last call to update.

Implements robot_controllers::Controller.

Definition at line 183 of file follow_joint_trajectory.cpp.

Member Data Documentation

std::vector<bool> robot_controllers::FollowJointTrajectoryController::continuous_
private

Definition at line 137 of file follow_joint_trajectory.h.

control_msgs::FollowJointTrajectoryFeedback robot_controllers::FollowJointTrajectoryController::feedback_
private

Definition at line 165 of file follow_joint_trajectory.h.

ros::Time robot_controllers::FollowJointTrajectoryController::goal_time
private

Definition at line 166 of file follow_joint_trajectory.h.

double robot_controllers::FollowJointTrajectoryController::goal_time_tolerance_
private

Definition at line 163 of file follow_joint_trajectory.h.

TrajectoryPoint robot_controllers::FollowJointTrajectoryController::goal_tolerance_
private

Definition at line 162 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::has_goal_tolerance_
private

Definition at line 161 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::has_path_tolerance_
private

action was preempted (has nothing to do with preempt() above).

Definition at line 158 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::initialized_
private

Definition at line 132 of file follow_joint_trajectory.h.

std::vector<std::string> robot_controllers::FollowJointTrajectoryController::joint_names_
private

Definition at line 136 of file follow_joint_trajectory.h.

std::vector<JointHandlePtr> robot_controllers::FollowJointTrajectoryController::joints_
private

Definition at line 135 of file follow_joint_trajectory.h.

TrajectoryPoint robot_controllers::FollowJointTrajectoryController::last_sample_
private

should we stop this controller when a path tolerance has been violated?

Definition at line 155 of file follow_joint_trajectory.h.

ControllerManager* robot_controllers::FollowJointTrajectoryController::manager_
private

Definition at line 133 of file follow_joint_trajectory.h.

TrajectoryPoint robot_controllers::FollowJointTrajectoryController::path_tolerance_
private

Definition at line 159 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::preempted_
private

Definition at line 156 of file follow_joint_trajectory.h.

boost::shared_ptr<TrajectorySampler> robot_controllers::FollowJointTrajectoryController::sampler_
private

Definition at line 140 of file follow_joint_trajectory.h.

boost::mutex robot_controllers::FollowJointTrajectoryController::sampler_mutex_
private

Definition at line 141 of file follow_joint_trajectory.h.

boost::shared_ptr<server_t> robot_controllers::FollowJointTrajectoryController::server_
private

Definition at line 138 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::stop_on_path_violation_
private

should we stop this controller when the action has terminated (or hold position)?

Definition at line 146 of file follow_joint_trajectory.h.

bool robot_controllers::FollowJointTrajectoryController::stop_with_action_
private

Definition at line 143 of file follow_joint_trajectory.h.


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


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39