Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction Class Reference

#include <fsrobo_r_joint_trajectory_action.h>

Public Member Functions

 FSRoboRJointTrajectoryAction ()
 Constructor. More...
 
void run ()
 Begin processing messages and publishing topics. More...
 
 ~FSRoboRJointTrajectoryAction ()
 Destructor. More...
 

Private Types

typedef actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > JointTractoryActionServer
 

Private Member Functions

void abortGoal ()
 Aborts the current action goal and sends a stop command (empty message) to the robot driver. More...
 
void cancelCB (JointTractoryActionServer::GoalHandle gh)
 Action server cancel callback method. More...
 
bool cancelMotionCB (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
 Cancel motion callback (executed when cancel_motion service is called) More...
 
void controllerStateCB (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
 Controller state callback (executed when feedback message received) More...
 
void goalCB (JointTractoryActionServer::GoalHandle gh)
 Action server goal callback method. More...
 
void robotStatusCB (const industrial_msgs::RobotStatusConstPtr &msg)
 Controller status callback (executed when robot status message received) More...
 
void watchdog (const ros::TimerEvent &e)
 Watch dog callback, used to detect robot driver failures. More...
 
bool withinGoalConstraints (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, const trajectory_msgs::JointTrajectory &traj)
 Controller status callback (executed when robot status message received) More...
 

Private Attributes

JointTractoryActionServer action_server_
 Internal action server. More...
 
JointTractoryActionServer::GoalHandle active_goal_
 Cache of the current active goal. More...
 
bool controller_alive_
 Controller was alive during the last watchdog interval. More...
 
trajectory_msgs::JointTrajectory current_traj_
 Cache of the current active trajectory. More...
 
double goal_threshold_
 The goal joint threshold used for determining if a robot is near it final destination. A single value is used for all joints. More...
 
bool has_active_goal_
 Indicates action has an active goal. More...
 
bool has_moved_once_
 Indicates that the robot has been in a moving state at least once since starting the current active trajectory. More...
 
std::vector< std::string > joint_names_
 The joint names associated with the robot the action is interfacing with. The joint names must be the same as expected by the robot driver. More...
 
industrial_msgs::RobotStatusConstPtr last_robot_status_
 Cache of the last subscribed status message. More...
 
control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_
 Cache of the last subscribed feedback message. More...
 
ros::NodeHandle node_
 Internal ROS node handle. More...
 
ros::Publisher pub_trajectory_command_
 Publishes desired trajectory (typically to the robot driver) More...
 
ros::ServiceServer srv_cancel_motion_
 Service to stop robot motion. More...
 
ros::Subscriber sub_robot_status_
 Subscribes to the robot status (typically published by the robot driver). More...
 
ros::Subscriber sub_trajectory_state_
 Subscribes to trajectory feedback (typically published by the robot driver). More...
 
ros::Time time_to_check_
 Time at which to start checking for completion of current goal, if one is active. More...
 
ros::Timer watchdog_timer_
 Watchdog time used to fail the action request if the robot driver is not responding. More...
 

Static Private Attributes

static const double DEFAULT_GOAL_THRESHOLD_ = 0.01
 The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e. radians or meters). More...
 
static const double WATCHDOG_PERIOD_ = 1.0
 The watchdog period (seconds) More...
 

Detailed Description

Definition at line 46 of file fsrobo_r_joint_trajectory_action.h.

Member Typedef Documentation

Definition at line 69 of file fsrobo_r_joint_trajectory_action.h.

Constructor & Destructor Documentation

fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::FSRoboRJointTrajectoryAction ( )

Constructor.

Definition at line 42 of file fsrobo_r_joint_trajectory_action.cpp.

fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::~FSRoboRJointTrajectoryAction ( )

Destructor.

Definition at line 69 of file fsrobo_r_joint_trajectory_action.cpp.

Member Function Documentation

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::abortGoal ( )
private

Aborts the current action goal and sends a stop command (empty message) to the robot driver.

Definition at line 300 of file fsrobo_r_joint_trajectory_action.cpp.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::cancelCB ( JointTractoryActionServer::GoalHandle  gh)
private

Action server cancel callback method.

Parameters
ghgoal handle

Definition at line 193 of file fsrobo_r_joint_trajectory_action.cpp.

bool fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::cancelMotionCB ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
)
private

Cancel motion callback (executed when cancel_motion service is called)

Parameters
reqservice request
resservice response
Returns
result

Definition at line 285 of file fsrobo_r_joint_trajectory_action.cpp.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::controllerStateCB ( const control_msgs::FollowJointTrajectoryFeedbackConstPtr &  msg)
private

Controller state callback (executed when feedback message received)

Parameters
msgjoint trajectory feedback message

Definition at line 213 of file fsrobo_r_joint_trajectory_action.cpp.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::goalCB ( JointTractoryActionServer::GoalHandle  gh)
private

Action server goal callback method.

Parameters
ghgoal handle

Definition at line 116 of file fsrobo_r_joint_trajectory_action.cpp.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::robotStatusCB ( const industrial_msgs::RobotStatusConstPtr &  msg)
private

Controller status callback (executed when robot status message received)

Parameters
msgrobot status message

Definition at line 73 of file fsrobo_r_joint_trajectory_action.cpp.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::run ( )
inline

Begin processing messages and publishing topics.

Definition at line 65 of file fsrobo_r_joint_trajectory_action.h.

void fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::watchdog ( const ros::TimerEvent e)
private

Watch dog callback, used to detect robot driver failures.

Parameters
etime event information

Definition at line 86 of file fsrobo_r_joint_trajectory_action.cpp.

bool fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::withinGoalConstraints ( const control_msgs::FollowJointTrajectoryFeedbackConstPtr &  msg,
const trajectory_msgs::JointTrajectory &  traj 
)
private

Controller status callback (executed when robot status message received)

Parameters
msgtrajectory feedback message
trajtrajectory to test against feedback
Returns
true if all joints are within goal contraints

Definition at line 311 of file fsrobo_r_joint_trajectory_action.cpp.

Member Data Documentation

JointTractoryActionServer fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::action_server_
private

Internal action server.

Definition at line 79 of file fsrobo_r_joint_trajectory_action.h.

JointTractoryActionServer::GoalHandle fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::active_goal_
private

Cache of the current active goal.

Definition at line 128 of file fsrobo_r_joint_trajectory_action.h.

bool fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::controller_alive_
private

Controller was alive during the last watchdog interval.

Definition at line 112 of file fsrobo_r_joint_trajectory_action.h.

trajectory_msgs::JointTrajectory fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::current_traj_
private

Cache of the current active trajectory.

Definition at line 132 of file fsrobo_r_joint_trajectory_action.h.

const double fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::DEFAULT_GOAL_THRESHOLD_ = 0.01
staticprivate

The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e. radians or meters).

Definition at line 138 of file fsrobo_r_joint_trajectory_action.h.

double fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::goal_threshold_
private

The goal joint threshold used for determining if a robot is near it final destination. A single value is used for all joints.

NOTE: This value is used in conjunction with the robot inMotion status (see industrial_msgs::RobotStatus) if it exists.

Definition at line 147 of file fsrobo_r_joint_trajectory_action.h.

bool fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::has_active_goal_
private

Indicates action has an active goal.

Definition at line 117 of file fsrobo_r_joint_trajectory_action.h.

bool fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::has_moved_once_
private

Indicates that the robot has been in a moving state at least once since starting the current active trajectory.

Definition at line 123 of file fsrobo_r_joint_trajectory_action.h.

std::vector<std::string> fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::joint_names_
private

The joint names associated with the robot the action is interfacing with. The joint names must be the same as expected by the robot driver.

Definition at line 154 of file fsrobo_r_joint_trajectory_action.h.

industrial_msgs::RobotStatusConstPtr fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::last_robot_status_
private

Cache of the last subscribed status message.

Definition at line 164 of file fsrobo_r_joint_trajectory_action.h.

control_msgs::FollowJointTrajectoryFeedbackConstPtr fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::last_trajectory_state_
private

Cache of the last subscribed feedback message.

Definition at line 159 of file fsrobo_r_joint_trajectory_action.h.

ros::NodeHandle fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::node_
private

Internal ROS node handle.

Definition at line 74 of file fsrobo_r_joint_trajectory_action.h.

ros::Publisher fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::pub_trajectory_command_
private

Publishes desired trajectory (typically to the robot driver)

Definition at line 84 of file fsrobo_r_joint_trajectory_action.h.

ros::ServiceServer fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::srv_cancel_motion_
private

Service to stop robot motion.

Definition at line 101 of file fsrobo_r_joint_trajectory_action.h.

ros::Subscriber fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::sub_robot_status_
private

Subscribes to the robot status (typically published by the robot driver).

Definition at line 96 of file fsrobo_r_joint_trajectory_action.h.

ros::Subscriber fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::sub_trajectory_state_
private

Subscribes to trajectory feedback (typically published by the robot driver).

Definition at line 90 of file fsrobo_r_joint_trajectory_action.h.

ros::Time fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::time_to_check_
private

Time at which to start checking for completion of current goal, if one is active.

Definition at line 170 of file fsrobo_r_joint_trajectory_action.h.

const double fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::WATCHDOG_PERIOD_ = 1.0
staticprivate

The watchdog period (seconds)

Definition at line 175 of file fsrobo_r_joint_trajectory_action.h.

ros::Timer fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::watchdog_timer_
private

Watchdog time used to fail the action request if the robot driver is not responding.

Definition at line 107 of file fsrobo_r_joint_trajectory_action.h.


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


fsrobo_r_driver
Author(s): F-ROSROBO
autogenerated on Sun Feb 9 2020 03:58:29