#include <action_server.h>
Public Member Functions | |
ActionServer (ActionTrajectoryFollowerInterface &follower, std::vector< std::string > &joint_names, double max_velocity) | |
virtual bool | consume (RTState_V1_6__7 &state) |
virtual bool | consume (RTState_V1_8 &state) |
virtual bool | consume (RTState_V3_0__1 &state) |
virtual bool | consume (RTState_V3_2__3 &state) |
virtual void | onRobotStateChange (RobotState state) |
void | start () |
Public Member Functions inherited from URRTPacketConsumer | |
virtual bool | consume (shared_ptr< RTPacket > packet) |
Public Member Functions inherited from IConsumer< RTPacket > | |
virtual void | onTimeout () |
virtual void | setupConsumer () |
virtual void | stopConsumer () |
virtual void | teardownConsumer () |
Private Types | |
typedef control_msgs::FollowJointTrajectoryAction | Action |
typedef actionlib::ServerGoalHandle< Action > | GoalHandle |
typedef control_msgs::FollowJointTrajectoryResult | Result |
typedef actionlib::ActionServer< Action > | Server |
Private Member Functions | |
void | interruptGoal (GoalHandle &gh) |
void | onCancel (GoalHandle gh) |
void | onGoal (GoalHandle gh) |
std::vector< size_t > | reorderMap (std::vector< std::string > goal_joints) |
void | trajectoryThread () |
bool | try_execute (GoalHandle &gh, Result &res) |
bool | updateState (RTShared &data) |
bool | validate (GoalHandle &gh, Result &res) |
bool | validateJoints (GoalHandle &gh, Result &res) |
bool | validateState (GoalHandle &gh, Result &res) |
bool | validateTrajectory (GoalHandle &gh, Result &res) |
Private Attributes | |
Server | as_ |
GoalHandle | curr_gh_ |
ActionTrajectoryFollowerInterface & | follower_ |
std::atomic< bool > | has_goal_ |
std::atomic< bool > | interrupt_traj_ |
std::vector< std::string > | joint_names_ |
std::set< std::string > | joint_set_ |
double | max_velocity_ |
ros::NodeHandle | nh_ |
std::array< double, 6 > | q_actual_ |
std::array< double, 6 > | qd_actual_ |
std::atomic< bool > | running_ |
RobotState | state_ |
std::condition_variable | tj_cv_ |
std::mutex | tj_mutex_ |
std::thread | tj_thread_ |
Definition at line 40 of file action_server.h.
|
private |
Definition at line 43 of file action_server.h.
|
private |
Definition at line 45 of file action_server.h.
|
private |
Definition at line 44 of file action_server.h.
|
private |
Definition at line 46 of file action_server.h.
ActionServer::ActionServer | ( | ActionTrajectoryFollowerInterface & | follower, |
std::vector< std::string > & | joint_names, | ||
double | max_velocity | ||
) |
Definition at line 24 of file action_server.cpp.
|
virtual |
Implements URRTPacketConsumer.
Definition at line 86 of file action_server.cpp.
|
virtual |
Implements URRTPacketConsumer.
Definition at line 90 of file action_server.cpp.
|
virtual |
Implements URRTPacketConsumer.
Definition at line 94 of file action_server.cpp.
|
virtual |
Implements URRTPacketConsumer.
Definition at line 98 of file action_server.cpp.
|
private |
|
private |
Definition at line 117 of file action_server.cpp.
|
private |
Definition at line 103 of file action_server.cpp.
|
virtual |
Implements Service.
Definition at line 50 of file action_server.cpp.
|
private |
Definition at line 263 of file action_server.cpp.
void ActionServer::start | ( | ) |
Definition at line 39 of file action_server.cpp.
|
private |
Definition at line 280 of file action_server.cpp.
|
private |
Definition at line 238 of file action_server.cpp.
|
private |
Definition at line 79 of file action_server.cpp.
|
private |
Definition at line 129 of file action_server.cpp.
|
private |
Definition at line 159 of file action_server.cpp.
|
private |
Definition at line 134 of file action_server.cpp.
|
private |
Definition at line 178 of file action_server.cpp.
|
private |
Definition at line 49 of file action_server.h.
|
private |
Definition at line 55 of file action_server.h.
|
private |
Definition at line 62 of file action_server.h.
|
private |
Definition at line 57 of file action_server.h.
|
private |
Definition at line 56 of file action_server.h.
|
private |
Definition at line 51 of file action_server.h.
|
private |
Definition at line 52 of file action_server.h.
|
private |
Definition at line 53 of file action_server.h.
|
private |
Definition at line 48 of file action_server.h.
|
private |
Definition at line 65 of file action_server.h.
|
private |
Definition at line 65 of file action_server.h.
|
private |
Definition at line 57 of file action_server.h.
|
private |
Definition at line 64 of file action_server.h.
|
private |
Definition at line 59 of file action_server.h.
|
private |
Definition at line 58 of file action_server.h.
|
private |
Definition at line 60 of file action_server.h.