$search

controller::JointSplineTrajectoryController Class Reference

#include <joint_spline_trajectory_controller.h>

Inheritance diagram for controller::JointSplineTrajectoryController:
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)
 JointSplineTrajectoryController ()
void starting ()
void update ()
 ~JointSplineTrajectoryController ()

Private Types

typedef std::vector< SegmentSpecifiedTrajectory

Private Member Functions

void commandCB (const trajectory_msgs::JointTrajectoryConstPtr &msg)
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
< realtime_tools::RealtimePublisher
< pr2_controllers_msgs::JointTrajectoryControllerState > > 
controller_state_publisher_
realtime_tools::RealtimeBox
< boost::shared_ptr< const
SpecifiedTrajectory > > 
current_trajectory_box_
std::vector
< pr2_mechanism_model::JointState * > 
joints_
ros::Time last_time_
int loop_count_
ros::NodeHandle node_
std::vector< control_toolbox::Pidpids_
std::vector< double > q
std::vector< double > qd
std::vector< double > qdd
pr2_mechanism_model::RobotStaterobot_
ros::ServiceServer serve_query_state_
ros::Subscriber sub_command_

Detailed Description

Definition at line 58 of file joint_spline_trajectory_controller.h.


Member Typedef Documentation

Definition at line 107 of file joint_spline_trajectory_controller.h.


Constructor & Destructor Documentation

controller::JointSplineTrajectoryController::JointSplineTrajectoryController (  ) 

Definition at line 142 of file joint_spline_trajectory_controller.cpp.

controller::JointSplineTrajectoryController::~JointSplineTrajectoryController (  ) 

Definition at line 147 of file joint_spline_trajectory_controller.cpp.


Member Function Documentation

void controller::JointSplineTrajectoryController::commandCB ( const trajectory_msgs::JointTrajectoryConstPtr msg  )  [private]

Definition at line 341 of file joint_spline_trajectory_controller.cpp.

bool controller::JointSplineTrajectoryController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
) [virtual]
bool controller::JointSplineTrajectoryController::queryStateService ( pr2_controllers_msgs::QueryTrajectoryState::Request req,
pr2_controllers_msgs::QueryTrajectoryState::Response resp 
) [private]

Definition at line 582 of file joint_spline_trajectory_controller.cpp.

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

Definition at line 625 of file joint_spline_trajectory_controller.cpp.

void controller::JointSplineTrajectoryController::starting (  )  [virtual]

Reimplemented from pr2_controller_interface::Controller.

Definition at line 247 of file joint_spline_trajectory_controller.cpp.

void controller::JointSplineTrajectoryController::update ( void   )  [virtual]

Member Data Documentation

Definition at line 88 of file joint_spline_trajectory_controller.h.

Definition at line 110 of file joint_spline_trajectory_controller.h.

Definition at line 74 of file joint_spline_trajectory_controller.h.

Definition at line 73 of file joint_spline_trajectory_controller.h.

Definition at line 71 of file joint_spline_trajectory_controller.h.

Definition at line 77 of file joint_spline_trajectory_controller.h.

Definition at line 75 of file joint_spline_trajectory_controller.h.

std::vector<double> controller::JointSplineTrajectoryController::q [private]

Definition at line 118 of file joint_spline_trajectory_controller.h.

std::vector<double> controller::JointSplineTrajectoryController::qd [private]

Definition at line 118 of file joint_spline_trajectory_controller.h.

std::vector<double> controller::JointSplineTrajectoryController::qdd [private]

Definition at line 118 of file joint_spline_trajectory_controller.h.

Definition at line 72 of file joint_spline_trajectory_controller.h.

Definition at line 84 of file joint_spline_trajectory_controller.h.

Definition at line 80 of file joint_spline_trajectory_controller.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Fri Mar 1 16:52:40 2013