28 #ifndef QB_MOVE_HARDWARE_INTERFACE_H 29 #define QB_MOVE_HARDWARE_INTERFACE_H 65 std::vector<std::string>
getJoints()
override;
120 #endif // QB_MOVE_HARDWARE_INTERFACE_H double position_ticks_to_radians_
std::vector< std::string > getJoints() override
Return the shaft position and stiffness preset joints whether command_with_position_and_preset_ is tr...
std::shared_ptr< qbMoveHW > qbMoveHWPtr
qbMoveHW()
Initialize the qb_device_hardware_interface::qbDeviceHW with the specific transmission interface and ...
bool command_with_position_and_preset_
int getMaxStiffness()
Parse the maximum value of stiffness of the device from the getInfo string.
void write(const ros::Time &time, const ros::Duration &period) override
Update the shaft joint limits and call the base method.
double preset_percent_to_radians_
~qbMoveHW() override
Do nothing.
void read(const ros::Time &time, const ros::Duration &period) override
Call the base method and nothing more.
qb_move_interactive_interface::qbMoveInteractive interactive_interface_
A simple interface that adds an interactive marker (to be used in rviz) with two controls to change r...
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Call the base method and nothing more.
The qbrobotics qbmove HardWare interface implements the specific structures to manage the communicati...
bool use_interactive_markers_
void updateShaftPositionLimits()
Update the shaft joint limits since they depend on the fixed motors limits and on the variable stiffn...