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

#include <joint_spline_trajectory_action_controller.hpp>

List of all members.

Classes

struct  Segment
struct  Spline

Public Member Functions

 JointTrajectoryActionController ()
 JointTrajectoryActionController ()
 ~JointTrajectoryActionController ()
 ~JointTrajectoryActionController ()

Private Types

typedef std::map< std::string,
ros::Publisher
JointPubMap
typedef std::vector
< trajectory_msgs::JointTrajectoryPoint > 
JointTrajectoryPointVec
typedef
actionlib::SimpleActionServer
< control_msgs::FollowJointTrajectoryAction > 
JTAS
typedef
actionlib::SimpleActionServer
< control_msgs::FollowJointTrajectoryAction > 
JTAS
typedef std::vector< SegmentSpecifiedTrajectory

Private Member Functions

void commandCB (const trajectory_msgs::JointTrajectoryConstPtr &msg)
void execute_trajectory (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
void execute_trajectory (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
bool getPosition (std::string joint_name, double &position)
void updateJointState ()

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::shared_ptr< JTASaction_server
ros::Subscriber command_sub
std::vector< ros::Publishercontroller_publishers
 This vector stores publishers to each joint controller.
ros::Publisher desired_joint_state_pusblisher
std::vector< std::string > joint_names_
JointPubMap joint_pub
ros::ServiceClient joint_state_client
std::map< std::string,
unsigned int > 
joint_state_idx_map
 stores a map of publisher associated with joint index
std::map< std::string, double > joint_state_map
std::map< std::string,
std::string > 
jointControllerMap
 stores a map of controller name and associated joints
std::map< std::string,
unsigned int > 
jointPubIdxMap
ros::Time last_time_
ros::NodeHandle nh
ros::NodeHandle nh_tilde
std::vector< double > q
std::vector< double > qd
std::vector< double > qdd
ros::Publisher sr_arm_target_pub
ros::Publisher sr_hand_target_pub
bool use_sendupdate
 store internal order of joints

Detailed Description

Definition at line 24 of file joint_spline_trajectory_action_controller.hpp.


Member Typedef Documentation

Definition at line 27 of file joint_trajectory_action_controller.hpp.

typedef std::vector<trajectory_msgs::JointTrajectoryPoint> shadowrobot::JointTrajectoryActionController::JointTrajectoryPointVec [private]

Definition at line 26 of file joint_trajectory_action_controller.hpp.

typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> shadowrobot::JointTrajectoryActionController::JTAS [private]

Definition at line 25 of file joint_trajectory_action_controller.hpp.

typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> shadowrobot::JointTrajectoryActionController::JTAS [private]

Constructor & Destructor Documentation


Member Function Documentation

void shadowrobot::JointTrajectoryActionController::commandCB ( const trajectory_msgs::JointTrajectoryConstPtr &  msg) [private]
void shadowrobot::JointTrajectoryActionController::execute_trajectory ( const control_msgs::FollowJointTrajectoryGoalConstPtr &  goal) [private]
void shadowrobot::JointTrajectoryActionController::execute_trajectory ( const control_msgs::FollowJointTrajectoryGoalConstPtr &  goal) [private]
bool shadowrobot::JointTrajectoryActionController::getPosition ( std::string  joint_name,
double &  position 
) [private]
void shadowrobot::JointTrajectoryActionController::sampleSplineWithTimeBounds ( const std::vector< double > &  coefficients,
double  duration,
double  time,
double &  position,
double &  velocity,
double &  acceleration 
) [static, private]

Member Data Documentation

This vector stores publishers to each joint controller.

Definition at line 41 of file joint_spline_trajectory_action_controller.hpp.

Definition at line 34 of file joint_trajectory_action_controller.hpp.

std::map<std::string,unsigned int> shadowrobot::JointTrajectoryActionController::joint_state_idx_map [private]

stores a map of publisher associated with joint index

Definition at line 44 of file joint_spline_trajectory_action_controller.hpp.

std::map<std::string,double> shadowrobot::JointTrajectoryActionController::joint_state_map [private]
std::map<std::string,std::string> shadowrobot::JointTrajectoryActionController::jointControllerMap [private]

stores a map of controller name and associated joints

Definition at line 42 of file joint_spline_trajectory_action_controller.hpp.

std::map<std::string,unsigned int> shadowrobot::JointTrajectoryActionController::jointPubIdxMap [private]
std::vector<double> shadowrobot::JointTrajectoryActionController::q [private]
std::vector<double> shadowrobot::JointTrajectoryActionController::qd [private]

store internal order of joints

Definition at line 45 of file joint_spline_trajectory_action_controller.hpp.


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


sr_mechanism_controllers
Author(s): Ugo Cupcic / ugo@shadowrobot.com , contact@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:54:40