Public Member Functions | Private Types | Private Member Functions | Private Attributes
robot_controllers::PointHeadController Class Reference

#include <point_head.h>

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

List of all members.

Public Member Functions

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

Private Types

typedef
actionlib::SimpleActionServer
< control_msgs::PointHeadAction > 
head_server_t

Private Member Functions

void executeCb (const control_msgs::PointHeadGoalConstPtr &goal)

Private Attributes

JointHandlePtr head_pan_
JointHandlePtr head_tilt_
bool initialized_
KDL::Tree kdl_tree_
TrajectoryPoint last_sample_
tf::TransformListener listener_
ControllerManagermanager_
bool preempted_
control_msgs::PointHeadResult result_
std::string root_link_
 action was preempted (has nothing to do with preempt() above
boost::shared_ptr
< TrajectorySampler
sampler_
boost::mutex sampler_mutex_
boost::shared_ptr< head_server_tserver_
bool stop_with_action_

Detailed Description

Definition at line 60 of file point_head.h.


Member Typedef Documentation

Definition at line 62 of file point_head.h.


Constructor & Destructor Documentation

Definition at line 65 of file point_head.h.

Definition at line 66 of file point_head.h.


Member Function Documentation

void robot_controllers::PointHeadController::executeCb ( const control_msgs::PointHeadGoalConstPtr &  goal) [private]

Definition at line 195 of file point_head.cpp.

std::vector< std::string > robot_controllers::PointHeadController::getClaimedNames ( ) [virtual]

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

Implements robot_controllers::Controller.

Definition at line 298 of file point_head.cpp.

std::vector< std::string > robot_controllers::PointHeadController::getCommandedNames ( ) [virtual]

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

Implements robot_controllers::Controller.

Definition at line 290 of file point_head.cpp.

virtual std::string robot_controllers::PointHeadController::getType ( ) [inline, virtual]

Get the type of this controller.

Reimplemented from robot_controllers::Controller.

Definition at line 109 of file point_head.h.

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 49 of file point_head.cpp.

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 156 of file point_head.cpp.

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 113 of file point_head.cpp.

bool robot_controllers::PointHeadController::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 132 of file point_head.cpp.

void robot_controllers::PointHeadController::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 162 of file point_head.cpp.


Member Data Documentation

Definition at line 143 of file point_head.h.

Definition at line 144 of file point_head.h.

Definition at line 123 of file point_head.h.

Definition at line 147 of file point_head.h.

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

Definition at line 139 of file point_head.h.

Definition at line 148 of file point_head.h.

Definition at line 124 of file point_head.h.

Definition at line 140 of file point_head.h.

control_msgs::PointHeadResult robot_controllers::PointHeadController::result_ [private]

Definition at line 126 of file point_head.h.

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

Definition at line 142 of file point_head.h.

Definition at line 127 of file point_head.h.

Definition at line 128 of file point_head.h.

Definition at line 145 of file point_head.h.

Definition at line 130 of file point_head.h.


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


robot_controllers
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:10