Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
ActionServer Class Reference

#include <action_server.h>

Inheritance diagram for ActionServer:
Inheritance graph
[legend]

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< ActionGoalHandle
 
typedef control_msgs::FollowJointTrajectoryResult Result
 
typedef actionlib::ActionServer< ActionServer
 

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_
 
ActionTrajectoryFollowerInterfacefollower_
 
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_
 

Detailed Description

Definition at line 40 of file action_server.h.

Member Typedef Documentation

typedef control_msgs::FollowJointTrajectoryAction ActionServer::Action
private

Definition at line 43 of file action_server.h.

Definition at line 45 of file action_server.h.

typedef control_msgs::FollowJointTrajectoryResult ActionServer::Result
private

Definition at line 44 of file action_server.h.

Definition at line 46 of file action_server.h.

Constructor & Destructor Documentation

ActionServer::ActionServer ( ActionTrajectoryFollowerInterface follower,
std::vector< std::string > &  joint_names,
double  max_velocity 
)

Definition at line 24 of file action_server.cpp.

Member Function Documentation

bool ActionServer::consume ( RTState_V1_6__7 state)
virtual

Implements URRTPacketConsumer.

Definition at line 86 of file action_server.cpp.

bool ActionServer::consume ( RTState_V1_8 state)
virtual

Implements URRTPacketConsumer.

Definition at line 90 of file action_server.cpp.

bool ActionServer::consume ( RTState_V3_0__1 state)
virtual

Implements URRTPacketConsumer.

Definition at line 94 of file action_server.cpp.

bool ActionServer::consume ( RTState_V3_2__3 state)
virtual

Implements URRTPacketConsumer.

Definition at line 98 of file action_server.cpp.

void ActionServer::interruptGoal ( GoalHandle gh)
private
void ActionServer::onCancel ( GoalHandle  gh)
private

Definition at line 117 of file action_server.cpp.

void ActionServer::onGoal ( GoalHandle  gh)
private

Definition at line 103 of file action_server.cpp.

void ActionServer::onRobotStateChange ( RobotState  state)
virtual

Implements Service.

Definition at line 50 of file action_server.cpp.

std::vector< size_t > ActionServer::reorderMap ( std::vector< std::string >  goal_joints)
private

Definition at line 263 of file action_server.cpp.

void ActionServer::start ( )

Definition at line 39 of file action_server.cpp.

void ActionServer::trajectoryThread ( )
private

Definition at line 280 of file action_server.cpp.

bool ActionServer::try_execute ( GoalHandle gh,
Result res 
)
private

Definition at line 238 of file action_server.cpp.

bool ActionServer::updateState ( RTShared data)
private

Definition at line 79 of file action_server.cpp.

bool ActionServer::validate ( GoalHandle gh,
Result res 
)
private

Definition at line 129 of file action_server.cpp.

bool ActionServer::validateJoints ( GoalHandle gh,
Result res 
)
private

Definition at line 159 of file action_server.cpp.

bool ActionServer::validateState ( GoalHandle gh,
Result res 
)
private

Definition at line 134 of file action_server.cpp.

bool ActionServer::validateTrajectory ( GoalHandle gh,
Result res 
)
private

Definition at line 178 of file action_server.cpp.

Member Data Documentation

Server ActionServer::as_
private

Definition at line 49 of file action_server.h.

GoalHandle ActionServer::curr_gh_
private

Definition at line 55 of file action_server.h.

ActionTrajectoryFollowerInterface& ActionServer::follower_
private

Definition at line 62 of file action_server.h.

std::atomic<bool> ActionServer::has_goal_
private

Definition at line 57 of file action_server.h.

std::atomic<bool> ActionServer::interrupt_traj_
private

Definition at line 56 of file action_server.h.

std::vector<std::string> ActionServer::joint_names_
private

Definition at line 51 of file action_server.h.

std::set<std::string> ActionServer::joint_set_
private

Definition at line 52 of file action_server.h.

double ActionServer::max_velocity_
private

Definition at line 53 of file action_server.h.

ros::NodeHandle ActionServer::nh_
private

Definition at line 48 of file action_server.h.

std::array<double, 6> ActionServer::q_actual_
private

Definition at line 65 of file action_server.h.

std::array<double, 6> ActionServer::qd_actual_
private

Definition at line 65 of file action_server.h.

std::atomic<bool> ActionServer::running_
private

Definition at line 57 of file action_server.h.

RobotState ActionServer::state_
private

Definition at line 64 of file action_server.h.

std::condition_variable ActionServer::tj_cv_
private

Definition at line 59 of file action_server.h.

std::mutex ActionServer::tj_mutex_
private

Definition at line 58 of file action_server.h.

std::thread ActionServer::tj_thread_
private

Definition at line 60 of file action_server.h.


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


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:01