#include <hw_interface.h>
Definition at line 70 of file hw_interface.h.
◆ SpeedScalingConfig
◆ HWInterface()
examples::HWInterface::HWInterface |
( |
| ) |
|
◆ ~HWInterface()
examples::HWInterface::~HWInterface |
( |
| ) |
|
◆ cancelCartesianInterpolation()
void examples::HWInterface::cancelCartesianInterpolation |
( |
| ) |
|
|
private |
Dummy implementation for canceling a running Cartesian interpolation on the robot.
Cancels the active goal of the CartesianTrajectoryController via preempt request.
Definition at line 195 of file hw_interface.cpp.
◆ cancelJointInterpolation()
void examples::HWInterface::cancelJointInterpolation |
( |
| ) |
|
|
private |
Dummy implementation for canceling a running joint interpolation on the robot.
Cancels the active goal of the JointTrajectoryController via preempt request.
Definition at line 185 of file hw_interface.cpp.
◆ dynamicReconfigureCallback()
void examples::HWInterface::dynamicReconfigureCallback |
( |
SpeedScalingConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
Use dynamic reconfigure to mimic the driver's speed scaling.
Note: The speed scaling interface used is not made for thread safety. In real driver code, that's not a problem, because robot drivers will operate in synchronous read-update-write cycles. Here, we use this interface under somewhat unrealistic "dynamic reconfigure" conditions for testing purposes.
- Parameters
-
config | The speed scaling from 0 to 1.0 |
level | Not used |
Definition at line 205 of file hw_interface.cpp.
◆ handleCartesianDone()
void examples::HWInterface::handleCartesianDone |
( |
const actionlib::SimpleClientGoalState & |
state, |
|
|
const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr & |
result |
|
) |
| |
|
private |
◆ handleCartesianFeedback()
void examples::HWInterface::handleCartesianFeedback |
( |
const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr & |
feedback | ) |
|
|
private |
◆ handleJointDone()
void examples::HWInterface::handleJointDone |
( |
const actionlib::SimpleClientGoalState & |
state, |
|
|
const control_msgs::FollowJointTrajectoryResultConstPtr & |
result |
|
) |
| |
|
private |
◆ handleJointFeedback()
void examples::HWInterface::handleJointFeedback |
( |
const control_msgs::FollowJointTrajectoryFeedbackConstPtr & |
feedback | ) |
|
|
private |
◆ read()
◆ startCartesianInterpolation()
Dummy implementation for Cartesian interpolation on the robot.
Passes this trajectory straight to a CartesianTrajectoryController to mimic external interpolation.
- Parameters
-
trajectory | The trajectory blob to forward to the vendor driver |
Definition at line 177 of file hw_interface.cpp.
◆ startJointInterpolation()
Dummy implementation for joint interpolation on the robot.
Passes this trajectory straight to a JointTrajectoryController to mimic external interpolation.
- Parameters
-
trajectory | The trajectory blob to forward to the vendor driver |
Definition at line 169 of file hw_interface.cpp.
◆ write()
◆ callback_type_
dynamic_reconfigure::Server<SpeedScalingConfig>::CallbackType examples::HWInterface::callback_type_ |
|
private |
◆ cart_state_interface_
◆ cart_traj_interface_
◆ cartesian_accel_
geometry_msgs::Accel examples::HWInterface::cartesian_accel_ |
|
private |
◆ cartesian_based_communication_
std::unique_ptr<actionlib::SimpleActionClient<cartesian_control_msgs::FollowCartesianTrajectoryAction> > examples::HWInterface::cartesian_based_communication_ |
|
private |
◆ cartesian_jerk_
geometry_msgs::Accel examples::HWInterface::cartesian_jerk_ |
|
private |
◆ cartesian_pose_
geometry_msgs::Pose examples::HWInterface::cartesian_pose_ |
|
private |
◆ cartesian_twist_
geometry_msgs::Twist examples::HWInterface::cartesian_twist_ |
|
private |
◆ cmd_
std::vector<double> examples::HWInterface::cmd_ |
|
private |
◆ eff_
std::vector<double> examples::HWInterface::eff_ |
|
private |
◆ frame_id_
std::string examples::HWInterface::frame_id_ |
|
private |
◆ jnt_pos_interface_
◆ jnt_state_interface_
◆ jnt_traj_interface_
◆ joint_based_communication_
◆ joint_handles_
◆ joint_names_
std::vector<std::string> examples::HWInterface::joint_names_ |
|
private |
Actuated joints in order from base to tip.
Definition at line 115 of file hw_interface.h.
◆ joint_state_handles_
◆ pos_
std::vector<double> examples::HWInterface::pos_ |
|
private |
◆ pose_cmd_
geometry_msgs::Pose examples::HWInterface::pose_cmd_ |
|
private |
◆ pose_cmd_interface_
◆ reconfig_server_
std::shared_ptr<dynamic_reconfigure::Server<SpeedScalingConfig> > examples::HWInterface::reconfig_server_ |
|
private |
◆ ref_frame_id_
std::string examples::HWInterface::ref_frame_id_ |
|
private |
◆ speed_scaling_
double examples::HWInterface::speed_scaling_ |
|
private |
◆ speedsc_interface_
◆ vel_
std::vector<double> examples::HWInterface::vel_ |
|
private |
The documentation for this class was generated from the following files: