#include <joint_trajectory_action.h>
Definition at line 48 of file joint_trajectory_action.h.
◆ JointTractoryActionServer
◆ JointTrajectoryAction()
industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::JointTrajectoryAction |
( |
| ) |
|
◆ ~JointTrajectoryAction()
industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::~JointTrajectoryAction |
( |
| ) |
|
◆ abortGoal()
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.
◆ cancelCB()
◆ controllerStateCB()
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.
◆ goalCB()
◆ robotStatusCB()
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::robotStatusCB |
( |
const industrial_msgs::RobotStatusConstPtr & |
msg | ) |
|
|
private |
◆ run()
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::run |
( |
| ) |
|
|
inline |
◆ watchdog()
void industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::watchdog |
( |
const ros::TimerEvent & |
e | ) |
|
|
private |
◆ withinGoalConstraints()
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.
◆ action_server_
◆ active_goal_
◆ controller_alive_
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::controller_alive_ |
|
private |
◆ current_traj_
trajectory_msgs::JointTrajectory industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::current_traj_ |
|
private |
◆ DEFAULT_GOAL_THRESHOLD_
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.
◆ goal_threshold_
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.
◆ has_active_goal_
bool industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::has_active_goal_ |
|
private |
◆ has_moved_once_
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.
◆ joint_names_
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.
◆ last_robot_status_
industrial_msgs::RobotStatusConstPtr industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::last_robot_status_ |
|
private |
◆ last_trajectory_state_
control_msgs::FollowJointTrajectoryFeedbackConstPtr industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::last_trajectory_state_ |
|
private |
◆ name_
std::string industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::name_ |
|
private |
◆ node_
ros::NodeHandle industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::node_ |
|
private |
◆ pub_trajectory_command_
ros::Publisher industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::pub_trajectory_command_ |
|
private |
◆ sub_robot_status_
ros::Subscriber industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::sub_robot_status_ |
|
private |
◆ sub_trajectory_state_
ros::Subscriber industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::sub_trajectory_state_ |
|
private |
◆ time_to_check_
ros::Time industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::time_to_check_ |
|
private |
◆ WATCHDOG_PERIOD_
const double industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::WATCHDOG_PERIOD_ = 1.0 |
|
staticprivate |
◆ watchdog_timer_
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: