#include <joint_trajectory_action.h>
Definition at line 48 of file joint_trajectory_action.h.
industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::JointTrajectoryAction |
( |
| ) |
|
industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::~JointTrajectoryAction |
( |
| ) |
|
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::abortGoal |
( |
| ) |
|
|
private |
Aborts the current action goal and sends a stop command (empty message) to the robot driver.
Definition at line 276 of file joint_trajectory_action.cpp.
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::controllerStateCB |
( |
const control_msgs::FollowJointTrajectoryFeedbackConstPtr & |
msg | ) |
|
|
private |
Controller state callback (executed when feedback message received)
- Parameters
-
msg | joint trajectory feedback message |
Definition at line 203 of file joint_trajectory_action.cpp.
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::robotStatusCB |
( |
const industrial_msgs::RobotStatusConstPtr & |
msg | ) |
|
|
private |
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::run |
( |
| ) |
|
|
inline |
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::watchdog |
( |
const ros::TimerEvent & |
e | ) |
|
|
private |
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::withinGoalConstraints |
( |
const control_msgs::FollowJointTrajectoryFeedbackConstPtr & |
msg, |
|
|
const trajectory_msgs::JointTrajectory & |
traj |
|
) |
| |
|
private |
Controller status callback (executed when robot status message received)
- Parameters
-
msg | trajectory feedback message |
traj | trajectory to test against feedback |
- Returns
- true if all joints are within goal contraints
Definition at line 287 of file joint_trajectory_action.cpp.
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::controller_alive_ |
|
private |
trajectory_msgs::JointTrajectory industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::current_traj_ |
|
private |
const double industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::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 140 of file joint_trajectory_action.h.
double industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::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 149 of file joint_trajectory_action.h.
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::has_active_goal_ |
|
private |
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::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 125 of file joint_trajectory_action.h.
std::vector<std::string> industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::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 156 of file joint_trajectory_action.h.
industrial_msgs::RobotStatusConstPtr industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::last_robot_status_ |
|
private |
control_msgs::FollowJointTrajectoryFeedbackConstPtr industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::last_trajectory_state_ |
|
private |
std::string industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::name_ |
|
private |
ros::NodeHandle industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::node_ |
|
private |
ros::Publisher industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::pub_trajectory_command_ |
|
private |
ros::Subscriber industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::sub_robot_status_ |
|
private |
ros::Subscriber industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::sub_trajectory_state_ |
|
private |
ros::Time industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::time_to_check_ |
|
private |
const double industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::WATCHDOG_PERIOD_ = 1.0 |
|
staticprivate |
ros::Timer industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::watchdog_timer_ |
|
private |
Watchdog time used to fail the action request if the robot driver is not responding.
Definition at line 109 of file joint_trajectory_action.h.
The documentation for this class was generated from the following files: