Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
controller::JointTrajectoryActionController Class Reference

#include <joint_trajectory_action_controller.h>

Inheritance diagram for controller::JointTrajectoryActionController:
Inheritance graph
[legend]

List of all members.

Classes

struct  Segment
struct  Spline

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 JointTrajectoryActionController ()
void starting ()
void update ()
 ~JointTrajectoryActionController ()

Private Types

typedef
actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction
FJTAS
typedef JTAS::GoalHandle GoalHandle
typedef FJTAS::GoalHandle GoalHandleFollow
typedef
actionlib::ActionServer
< pr2_controllers_msgs::JointTrajectoryAction
JTAS
typedef RTServerGoalHandle
< pr2_controllers_msgs::JointTrajectoryAction
RTGoalHandle
typedef RTServerGoalHandle
< control_msgs::FollowJointTrajectoryAction
RTGoalHandleFollow
typedef std::vector< SegmentSpecifiedTrajectory

Private Member Functions

void cancelCB (GoalHandle gh)
void cancelCBFollow (GoalHandleFollow gh)
void commandCB (const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void commandTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &traj, boost::shared_ptr< RTGoalHandle > gh=boost::shared_ptr< RTGoalHandle >((RTGoalHandle *) NULL), boost::shared_ptr< RTGoalHandleFollow > gh_follow=boost::shared_ptr< RTGoalHandleFollow >((RTGoalHandleFollow *) NULL))
void goalCB (GoalHandle gh)
void goalCBFollow (GoalHandleFollow gh)
void preemptActiveGoal ()
bool queryStateService (pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)

Static Private Member Functions

static void sampleSplineWithTimeBounds (const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)

Private Attributes

boost::scoped_ptr< JTASaction_server_
boost::scoped_ptr< FJTASaction_server_follow_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< pr2_controllers_msgs::JointTrajectoryControllerState > > 
controller_state_publisher_
realtime_tools::RealtimeBox
< boost::shared_ptr< const
SpecifiedTrajectory > > 
current_trajectory_box_
double default_goal_time_constraint_
std::vector< JointTolerancedefault_goal_tolerance_
std::vector< JointTolerancedefault_trajectory_tolerance_
ros::Timer goal_handle_timer_
std::vector
< pr2_mechanism_model::JointState * > 
joints_
ros::Time last_time_
int loop_count_
std::vector< double > masses_
ros::NodeHandle node_
std::vector< boost::shared_ptr
< filters::FilterChain< double > > > 
output_filters_
std::vector< control_toolbox::Pidpids_
std::vector
< control_toolbox::LimitedProxy
proxies_
std::vector< bool > proxies_enabled_
std::vector< double > q
std::vector< double > qd
std::vector< double > qdd
pr2_mechanism_model::RobotStaterobot_
boost::shared_ptr< RTGoalHandlert_active_goal_
boost::shared_ptr
< RTGoalHandleFollow
rt_active_goal_follow_
ros::ServiceServer serve_query_state_
ros::Subscriber sub_command_

Detailed Description

Definition at line 161 of file joint_trajectory_action_controller.h.


Member Typedef Documentation

Definition at line 169 of file joint_trajectory_action_controller.h.

Definition at line 165 of file joint_trajectory_action_controller.h.

Definition at line 170 of file joint_trajectory_action_controller.h.

Definition at line 164 of file joint_trajectory_action_controller.h.

Definition at line 166 of file joint_trajectory_action_controller.h.

Definition at line 171 of file joint_trajectory_action_controller.h.

Definition at line 258 of file joint_trajectory_action_controller.h.


Constructor & Destructor Documentation

Definition at line 142 of file joint_trajectory_action_controller.cpp.

Definition at line 147 of file joint_trajectory_action_controller.cpp.


Member Function Documentation

Definition at line 1024 of file joint_trajectory_action_controller.cpp.

Definition at line 1042 of file joint_trajectory_action_controller.cpp.

void controller::JointTrajectoryActionController::commandCB ( const trajectory_msgs::JointTrajectory::ConstPtr &  msg) [private]

Definition at line 500 of file joint_trajectory_action_controller.cpp.

void controller::JointTrajectoryActionController::commandTrajectory ( const trajectory_msgs::JointTrajectory::ConstPtr &  traj,
boost::shared_ptr< RTGoalHandle gh = boost::shared_ptr<RTGoalHandle>((RTGoalHandle*)NULL),
boost::shared_ptr< RTGoalHandleFollow gh_follow = boost::shared_ptr<RTGoalHandleFollow>((RTGoalHandleFollow*)NULL) 
) [private]

Definition at line 506 of file joint_trajectory_action_controller.cpp.

Definition at line 968 of file joint_trajectory_action_controller.cpp.

Definition at line 994 of file joint_trajectory_action_controller.cpp.

Definition at line 940 of file joint_trajectory_action_controller.cpp.

Definition at line 853 of file joint_trajectory_action_controller.cpp.

void controller::JointTrajectoryActionController::sampleSplineWithTimeBounds ( const std::vector< double > &  coefficients,
double  duration,
double  time,
double &  position,
double &  velocity,
double &  acceleration 
) [static, private]

Definition at line 896 of file joint_trajectory_action_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 313 of file joint_trajectory_action_controller.cpp.


Member Data Documentation

Definition at line 218 of file joint_trajectory_action_controller.h.

Definition at line 219 of file joint_trajectory_action_controller.h.

Definition at line 216 of file joint_trajectory_action_controller.h.

realtime_tools::RealtimeBox< boost::shared_ptr<const SpecifiedTrajectory> > controller::JointTrajectoryActionController::current_trajectory_box_ [private]

Definition at line 261 of file joint_trajectory_action_controller.h.

Definition at line 195 of file joint_trajectory_action_controller.h.

Definition at line 194 of file joint_trajectory_action_controller.h.

Definition at line 193 of file joint_trajectory_action_controller.h.

Definition at line 224 of file joint_trajectory_action_controller.h.

Definition at line 187 of file joint_trajectory_action_controller.h.

Definition at line 186 of file joint_trajectory_action_controller.h.

Definition at line 184 of file joint_trajectory_action_controller.h.

Definition at line 188 of file joint_trajectory_action_controller.h.

Definition at line 205 of file joint_trajectory_action_controller.h.

Definition at line 203 of file joint_trajectory_action_controller.h.

Definition at line 189 of file joint_trajectory_action_controller.h.

Definition at line 191 of file joint_trajectory_action_controller.h.

Definition at line 190 of file joint_trajectory_action_controller.h.

Definition at line 269 of file joint_trajectory_action_controller.h.

Definition at line 269 of file joint_trajectory_action_controller.h.

Definition at line 269 of file joint_trajectory_action_controller.h.

Definition at line 185 of file joint_trajectory_action_controller.h.

Definition at line 226 of file joint_trajectory_action_controller.h.

Definition at line 227 of file joint_trajectory_action_controller.h.

Definition at line 212 of file joint_trajectory_action_controller.h.

Definition at line 208 of file joint_trajectory_action_controller.h.


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


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Fri Jan 3 2014 11:41:37