Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
BaseTrajectoryActionController Class Reference

#include <pr2_base_trajectory_action.h>

List of all members.

Classes

class  JointState
struct  Segment
struct  Spline

Public Member Functions

 BaseTrajectoryActionController (const ros::NodeHandle &n)
bool init ()
void starting ()
void update ()
 ~BaseTrajectoryActionController ()

Private Types

typedef JTAS::GoalHandle GoalHandle
typedef
actionlib::ActionServer
< pr2_controllers_msgs::JointTrajectoryAction > 
JTAS
typedef std::vector< SegmentSpecifiedTrajectory

Private Member Functions

void cancelCB (GoalHandle gh)
void commandCB (const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void commandTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &traj, boost::shared_ptr< GoalHandle > gh=boost::shared_ptr< GoalHandle >((GoalHandle *) NULL))
void goalCB (GoalHandle gh)
void odomCB (const nav_msgs::Odometry::ConstPtr &msg)

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::shared_ptr< GoalHandleactive_goal_
boost::shared_ptr< const
SpecifiedTrajectory
current_trajectory_
std::vector< double > e
std::vector< double > ed
std::vector< double > edd
std::vector< double > goal_constraints_
ros::Timer goal_handle_timer_
double goal_threshold_
double goal_time_constraint_
std::vector< JointState * > joints_
ros::Time last_time_
ros::NodeHandle node_
ros::Publisher pub_command_
std::vector< double > q
std::vector< double > qd
std::vector< double > qdd
ros::Time robot_time_
double stopped_velocity_tolerance_
ros::Subscriber sub_odom_
std::vector< double > trajectory_constraints_
bool use_pid
JointState x_joint_
JointState y_joint_
JointState z_joint_

Detailed Description

Definition at line 54 of file pr2_base_trajectory_action.h.


Member Typedef Documentation

Definition at line 57 of file pr2_base_trajectory_action.h.

typedef actionlib::ActionServer<pr2_controllers_msgs::JointTrajectoryAction> BaseTrajectoryActionController::JTAS [private]

Definition at line 56 of file pr2_base_trajectory_action.h.

Definition at line 123 of file pr2_base_trajectory_action.h.


Constructor & Destructor Documentation

Definition at line 154 of file pr2_base_trajectory_action.cpp.

Definition at line 164 of file pr2_base_trajectory_action.cpp.


Member Function Documentation

Definition at line 749 of file pr2_base_trajectory_action.cpp.

void BaseTrajectoryActionController::commandCB ( const trajectory_msgs::JointTrajectory::ConstPtr &  msg) [private]
void BaseTrajectoryActionController::commandTrajectory ( const trajectory_msgs::JointTrajectory::ConstPtr &  traj,
boost::shared_ptr< GoalHandle gh = boost::shared_ptr<GoalHandle>((GoalHandle*)NULL) 
) [private]

Definition at line 392 of file pr2_base_trajectory_action.cpp.

Definition at line 717 of file pr2_base_trajectory_action.cpp.

Definition at line 171 of file pr2_base_trajectory_action.cpp.

void BaseTrajectoryActionController::odomCB ( const nav_msgs::Odometry::ConstPtr &  msg) [private]

Definition at line 652 of file pr2_base_trajectory_action.cpp.

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

Definition at line 664 of file pr2_base_trajectory_action.cpp.

Definition at line 223 of file pr2_base_trajectory_action.cpp.

Definition at line 239 of file pr2_base_trajectory_action.cpp.


Member Data Documentation

Definition at line 98 of file pr2_base_trajectory_action.h.

Definition at line 103 of file pr2_base_trajectory_action.h.

Definition at line 125 of file pr2_base_trajectory_action.h.

Definition at line 134 of file pr2_base_trajectory_action.h.

Definition at line 134 of file pr2_base_trajectory_action.h.

Definition at line 134 of file pr2_base_trajectory_action.h.

Definition at line 87 of file pr2_base_trajectory_action.h.

Definition at line 101 of file pr2_base_trajectory_action.h.

Definition at line 85 of file pr2_base_trajectory_action.h.

Definition at line 84 of file pr2_base_trajectory_action.h.

Definition at line 83 of file pr2_base_trajectory_action.h.

Definition at line 82 of file pr2_base_trajectory_action.h.

Definition at line 90 of file pr2_base_trajectory_action.h.

Definition at line 93 of file pr2_base_trajectory_action.h.

Definition at line 133 of file pr2_base_trajectory_action.h.

Definition at line 133 of file pr2_base_trajectory_action.h.

Definition at line 133 of file pr2_base_trajectory_action.h.

Definition at line 82 of file pr2_base_trajectory_action.h.

Definition at line 86 of file pr2_base_trajectory_action.h.

Definition at line 96 of file pr2_base_trajectory_action.h.

Definition at line 88 of file pr2_base_trajectory_action.h.

Definition at line 80 of file pr2_base_trajectory_action.h.

Definition at line 81 of file pr2_base_trajectory_action.h.

Definition at line 81 of file pr2_base_trajectory_action.h.

Definition at line 81 of file pr2_base_trajectory_action.h.


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


pr2_base_trajectory_action
Author(s): saito
autogenerated on Wed Sep 16 2015 10:31:51