37 #ifndef JOINT_TRAJECTORY_ACTION_CONTROLLER_H__ 38 #define JOINT_TRAJECTORY_ACTION_CONTROLLER_H__ 42 #include <boost/scoped_ptr.hpp> 43 #include <boost/thread/recursive_mutex.hpp> 44 #include <boost/thread/condition.hpp> 56 #include <control_msgs/FollowJointTrajectoryAction.h> 57 #include <trajectory_msgs/JointTrajectory.h> 58 #include <pr2_controllers_msgs/QueryTrajectoryState.h> 59 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h> 60 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 65 template <
class Action>
88 : req_abort_(false), req_succeed_(false), gh_(gh), preallocated_result_(preallocated_result)
90 if (!preallocated_result_)
91 preallocated_result_.reset(
new Result);
92 if (!preallocated_feedback_)
93 preallocated_feedback_.reset(
new Feedback);
96 void setAborted(ResultConstPtr result = ResultConstPtr((Result*)NULL))
98 if (!req_succeed_ && !req_abort_)
100 req_result_ = result;
105 void setSucceeded(ResultConstPtr result = ResultConstPtr((Result*)NULL))
107 if (!req_succeed_ && !req_abort_)
109 req_result_ = result;
121 using namespace actionlib_msgs;
125 if (req_abort_ && gs.status == GoalStatus::ACTIVE)
132 else if (req_succeed_ && gs.status == GoalStatus::ACTIVE)
146 JointTolerance(
double _position = 0,
double _velocity = 0,
double _acceleration = 0) :
147 position(_position), velocity(_velocity), acceleration(_acceleration)
151 bool violated(
double p_err,
double v_err = 0,
double a_err = 0)
const 154 (position > 0 && fabs(p_err) > position) ||
155 (velocity > 0 && fabs(v_err) > velocity) ||
156 (acceleration > 0 && fabs(a_err) > acceleration);
191 std::vector<pr2_mechanism_model::JointState*>
joints_;
193 std::vector<control_toolbox::Pid>
pids_;
195 std::vector<control_toolbox::LimitedProxy>
proxies_;
211 void commandCB(
const trajectory_msgs::JointTrajectory::ConstPtr &msg);
214 bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req,
215 pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
224 void goalCB(GoalHandle gh);
225 void cancelCB(GoalHandle gh);
226 void goalCBFollow(GoalHandleFollow gh);
227 void cancelCBFollow(GoalHandleFollow gh);
235 void commandTrajectory(
const trajectory_msgs::JointTrajectory::ConstPtr &traj,
239 void preemptActiveGoal();
273 std::vector<double> q, qd,
qdd;
278 static void sampleSplineWithTimeBounds(
const std::vector<double>& coefficients,
double duration,
double time,
279 double& position,
double& velocity,
double& acceleration);
ACTION_DEFINITION(Action)
actionlib::ServerGoalHandle< Action > GoalHandle
std::vector< Spline > splines
RTServerGoalHandle< pr2_controllers_msgs::JointTrajectoryAction > RTGoalHandle
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
boost::shared_ptr< Feedback > FeedbackPtr
std::vector< bool > proxies_enabled_
RTServerGoalHandle(GoalHandle &gh, const ResultPtr &preallocated_result=ResultPtr((Result *) NULL))
std::vector< JointTolerance > default_goal_tolerance_
FJTAS::GoalHandle GoalHandleFollow
void setAborted(ResultConstPtr result=ResultConstPtr((Result *) NULL))
boost::shared_ptr< const Goal > getGoal() const
JointTolerance(double _position=0, double _velocity=0, double _acceleration=0)
std::vector< JointTolerance > default_trajectory_tolerance_
std::vector< double > coef
FeedbackPtr preallocated_feedback_
std::vector< control_toolbox::Pid > pids_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< JointTolerance > goal_tolerance
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
boost::scoped_ptr< FJTAS > action_server_follow_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
std::vector< double > masses_
void setSucceeded(ResultConstPtr result=ResultConstPtr((Result *) NULL))
ResultConstPtr req_result_
pr2_mechanism_model::RobotState * robot_
ResultPtr preallocated_result_
boost::shared_ptr< RTGoalHandleFollow > rt_active_goal_follow_
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > FJTAS
JTAS::GoalHandle GoalHandle
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< RTGoalHandle > gh
std::vector< Segment > SpecifiedTrajectory
boost::shared_ptr< RTGoalHandle > rt_active_goal_
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
boost::shared_ptr< RTGoalHandleFollow > gh_follow
RTServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RTGoalHandleFollow
std::vector< double > qdd
boost::shared_ptr< Result > ResultPtr
std::vector< control_toolbox::LimitedProxy > proxies_
ros::Timer goal_handle_timer_
ros::ServiceServer serve_query_state_
std::vector< JointTolerance > trajectory_tolerance
std::vector< boost::shared_ptr< filters::FilterChain< double > > > output_filters_
double default_goal_time_constraint_
boost::scoped_ptr< JTAS > action_server_
double goal_time_tolerance
bool violated(double p_err, double v_err=0, double a_err=0) const
ros::Subscriber sub_command_
actionlib_msgs::GoalStatus getGoalStatus() const
std::vector< pr2_mechanism_model::JointState * > joints_
void runNonRT(const ros::TimerEvent &te)