Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
examples::HWInterface Class Reference

#include <hw_interface.h>

Inheritance diagram for examples::HWInterface:
Inheritance graph
[legend]

Public Member Functions

 HWInterface ()
 
void read (const ros::Time &time, const ros::Duration &period) override
 
void write (const ros::Time &time, const ros::Duration &period) override
 
 ~HWInterface ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &, ros::NodeHandle &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual SwitchState switchResult () const
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual ~RobotHW ()=default
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Private Types

using SpeedScalingConfig = pass_through_controllers::SpeedScalingConfig
 

Private Member Functions

void cancelCartesianInterpolation ()
 Dummy implementation for canceling a running Cartesian interpolation on the robot. More...
 
void cancelJointInterpolation ()
 Dummy implementation for canceling a running joint interpolation on the robot. More...
 
void dynamicReconfigureCallback (SpeedScalingConfig &config, uint32_t level)
 Use dynamic reconfigure to mimic the driver's speed scaling. More...
 
void handleCartesianDone (const actionlib::SimpleClientGoalState &state, const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr &result)
 
void handleCartesianFeedback (const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr &feedback)
 
void handleJointDone (const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
 
void handleJointFeedback (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
 
void startCartesianInterpolation (const hardware_interface::CartesianTrajectory &trajectory)
 Dummy implementation for Cartesian interpolation on the robot. More...
 
void startJointInterpolation (const hardware_interface::JointTrajectory &trajectory)
 Dummy implementation for joint interpolation on the robot. More...
 

Private Attributes

dynamic_reconfigure::Server< SpeedScalingConfig >::CallbackType callback_type_
 
ros_controllers_cartesian::CartesianStateInterface cart_state_interface_
 
hardware_interface::CartesianTrajectoryInterface cart_traj_interface_
 
geometry_msgs::Accel cartesian_accel_
 
std::unique_ptr< actionlib::SimpleActionClient< cartesian_control_msgs::FollowCartesianTrajectoryAction > > cartesian_based_communication_
 
geometry_msgs::Accel cartesian_jerk_
 
geometry_msgs::Pose cartesian_pose_
 
geometry_msgs::Twist cartesian_twist_
 
std::vector< double > cmd_
 
std::vector< double > eff_
 
std::string frame_id_
 
hardware_interface::PositionJointInterface jnt_pos_interface_
 
hardware_interface::JointStateInterface jnt_state_interface_
 
hardware_interface::JointTrajectoryInterface jnt_traj_interface_
 
std::unique_ptr< actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > > joint_based_communication_
 
std::vector< hardware_interface::JointHandlejoint_handles_
 
std::vector< std::string > joint_names_
 Actuated joints in order from base to tip. More...
 
std::vector< hardware_interface::JointStateHandlejoint_state_handles_
 
std::vector< double > pos_
 
geometry_msgs::Pose pose_cmd_
 
ros_controllers_cartesian::PoseCommandInterface pose_cmd_interface_
 
std::shared_ptr< dynamic_reconfigure::Server< SpeedScalingConfig > > reconfig_server_
 
std::string ref_frame_id_
 
double speed_scaling_
 
scaled_controllers::SpeedScalingInterface speedsc_interface_
 
std::vector< double > vel_
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 
- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
std::vector< ResourceManagerBase * > interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 70 of file hw_interface.h.

Member Typedef Documentation

◆ SpeedScalingConfig

using examples::HWInterface::SpeedScalingConfig = pass_through_controllers::SpeedScalingConfig
private

Definition at line 139 of file hw_interface.h.

Constructor & Destructor Documentation

◆ HWInterface()

examples::HWInterface::HWInterface ( )

Definition at line 43 of file hw_interface.cpp.

◆ ~HWInterface()

examples::HWInterface::~HWInterface ( )

Definition at line 155 of file hw_interface.cpp.

Member Function Documentation

◆ 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
configThe speed scaling from 0 to 1.0
levelNot 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

Definition at line 240 of file hw_interface.cpp.

◆ handleCartesianFeedback()

void examples::HWInterface::handleCartesianFeedback ( const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr &  feedback)
private

Definition at line 234 of file hw_interface.cpp.

◆ handleJointDone()

void examples::HWInterface::handleJointDone ( const actionlib::SimpleClientGoalState state,
const control_msgs::FollowJointTrajectoryResultConstPtr &  result 
)
private

Definition at line 216 of file hw_interface.cpp.

◆ handleJointFeedback()

void examples::HWInterface::handleJointFeedback ( const control_msgs::FollowJointTrajectoryFeedbackConstPtr &  feedback)
private

Definition at line 211 of file hw_interface.cpp.

◆ read()

void examples::HWInterface::read ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 159 of file hw_interface.cpp.

◆ startCartesianInterpolation()

void examples::HWInterface::startCartesianInterpolation ( const hardware_interface::CartesianTrajectory trajectory)
private

Dummy implementation for Cartesian interpolation on the robot.

Passes this trajectory straight to a CartesianTrajectoryController to mimic external interpolation.

Parameters
trajectoryThe trajectory blob to forward to the vendor driver

Definition at line 177 of file hw_interface.cpp.

◆ startJointInterpolation()

void examples::HWInterface::startJointInterpolation ( const hardware_interface::JointTrajectory trajectory)
private

Dummy implementation for joint interpolation on the robot.

Passes this trajectory straight to a JointTrajectoryController to mimic external interpolation.

Parameters
trajectoryThe trajectory blob to forward to the vendor driver

Definition at line 169 of file hw_interface.cpp.

◆ write()

void examples::HWInterface::write ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Reimplemented from hardware_interface::RobotHW.

Definition at line 164 of file hw_interface.cpp.

Member Data Documentation

◆ callback_type_

dynamic_reconfigure::Server<SpeedScalingConfig>::CallbackType examples::HWInterface::callback_type_
private

Definition at line 156 of file hw_interface.h.

◆ cart_state_interface_

ros_controllers_cartesian::CartesianStateInterface examples::HWInterface::cart_state_interface_
private

Definition at line 118 of file hw_interface.h.

◆ cart_traj_interface_

hardware_interface::CartesianTrajectoryInterface examples::HWInterface::cart_traj_interface_
private

Definition at line 123 of file hw_interface.h.

◆ cartesian_accel_

geometry_msgs::Accel examples::HWInterface::cartesian_accel_
private

Definition at line 161 of file hw_interface.h.

◆ cartesian_based_communication_

std::unique_ptr<actionlib::SimpleActionClient<cartesian_control_msgs::FollowCartesianTrajectoryAction> > examples::HWInterface::cartesian_based_communication_
private

Definition at line 176 of file hw_interface.h.

◆ cartesian_jerk_

geometry_msgs::Accel examples::HWInterface::cartesian_jerk_
private

Definition at line 162 of file hw_interface.h.

◆ cartesian_pose_

geometry_msgs::Pose examples::HWInterface::cartesian_pose_
private

Definition at line 159 of file hw_interface.h.

◆ cartesian_twist_

geometry_msgs::Twist examples::HWInterface::cartesian_twist_
private

Definition at line 160 of file hw_interface.h.

◆ cmd_

std::vector<double> examples::HWInterface::cmd_
private

Definition at line 127 of file hw_interface.h.

◆ eff_

std::vector<double> examples::HWInterface::eff_
private

Definition at line 130 of file hw_interface.h.

◆ frame_id_

std::string examples::HWInterface::frame_id_
private

Definition at line 136 of file hw_interface.h.

◆ jnt_pos_interface_

hardware_interface::PositionJointInterface examples::HWInterface::jnt_pos_interface_
private

Definition at line 121 of file hw_interface.h.

◆ jnt_state_interface_

hardware_interface::JointStateInterface examples::HWInterface::jnt_state_interface_
private

Definition at line 120 of file hw_interface.h.

◆ jnt_traj_interface_

hardware_interface::JointTrajectoryInterface examples::HWInterface::jnt_traj_interface_
private

Definition at line 122 of file hw_interface.h.

◆ joint_based_communication_

std::unique_ptr<actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> > examples::HWInterface::joint_based_communication_
private

Definition at line 169 of file hw_interface.h.

◆ joint_handles_

std::vector<hardware_interface::JointHandle> examples::HWInterface::joint_handles_
private

Definition at line 165 of file hw_interface.h.

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

std::vector<hardware_interface::JointStateHandle> examples::HWInterface::joint_state_handles_
private

Definition at line 166 of file hw_interface.h.

◆ pos_

std::vector<double> examples::HWInterface::pos_
private

Definition at line 128 of file hw_interface.h.

◆ pose_cmd_

geometry_msgs::Pose examples::HWInterface::pose_cmd_
private

Definition at line 132 of file hw_interface.h.

◆ pose_cmd_interface_

ros_controllers_cartesian::PoseCommandInterface examples::HWInterface::pose_cmd_interface_
private

Definition at line 119 of file hw_interface.h.

◆ reconfig_server_

std::shared_ptr<dynamic_reconfigure::Server<SpeedScalingConfig> > examples::HWInterface::reconfig_server_
private

Definition at line 155 of file hw_interface.h.

◆ ref_frame_id_

std::string examples::HWInterface::ref_frame_id_
private

Definition at line 135 of file hw_interface.h.

◆ speed_scaling_

double examples::HWInterface::speed_scaling_
private

Definition at line 131 of file hw_interface.h.

◆ speedsc_interface_

scaled_controllers::SpeedScalingInterface examples::HWInterface::speedsc_interface_
private

Definition at line 124 of file hw_interface.h.

◆ vel_

std::vector<double> examples::HWInterface::vel_
private

Definition at line 129 of file hw_interface.h.


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


pass_through_controllers
Author(s):
autogenerated on Tue Oct 15 2024 02:10:52