37 #ifndef JOINT_TRAJECTORY_CONTROLLER_H__ 38 #define JOINT_TRAJECTORY_CONTROLLER_H__ 42 #include <boost/scoped_ptr.hpp> 43 #include <boost/thread/recursive_mutex.hpp> 44 #include <boost/thread/condition.hpp> 51 #include "trajectory_msgs/JointTrajectory.h" 53 #include "pr2_controllers_msgs/QueryTrajectoryState.h" 54 #include "pr2_controllers_msgs/JointTrajectoryControllerState.h" 74 std::vector<pr2_mechanism_model::JointState*>
joints_;
75 std::vector<control_toolbox::Pid>
pids_;
79 void commandCB(
const trajectory_msgs::JointTrajectoryConstPtr &msg);
83 pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
124 double& position,
double& velocity,
double& acceleration);
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
ros::Subscriber sub_command_
~JointSplineTrajectoryController()
static void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
std::vector< pr2_mechanism_model::JointState * > joints_
JointSplineTrajectoryController()
std::vector< control_toolbox::Pid > pids_
pr2_mechanism_model::RobotState * robot_
bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
std::vector< double > coef
std::vector< double > qdd
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
std::vector< Segment > SpecifiedTrajectory
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
ros::ServiceServer serve_query_state_
std::vector< Spline > splines
void commandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)