33 : qbDeviceHW(
std::make_shared<
qb_move_transmission_interface::qbMoveTransmission>(), {
"motor_1_joint",
"motor_2_joint",
"shaft_joint"}, {
"motor_1_joint",
"motor_2_joint",
"shaft_joint",
"stiffness_preset_virtual_joint"}) {
49 std::smatch match_row, match_value;
50 std::string device_info(
getInfo());
51 if (std::regex_search(device_info, match_row, std::regex(
"Max stiffness: [[:digit:]]+"))) {
52 std::string max_stiffness(match_row[0]);
53 std::regex_search(max_stiffness, match_value, std::regex(
"[[:digit:]]+"));
54 return std::stoi(match_value[0]);
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...
qb_device_hardware_interface::qbDeviceHWResources joints_
const TransmissionPtr & getTransmission()
qbMoveHW()
Initialize the qb_device_hardware_interface::qbDeviceHW with the specific transmission interface and ...
std::vector< int > encoder_resolutions
bool command_with_position_and_preset_
std::vector< int > position_limits
std::vector< double > positions
std::vector< double > commands
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.
void initMarkers(ros::NodeHandle &root_nh, const std::string &device_name, const std::vector< std::string > &joint_names)
Initialize the interactive_markers::InteractiveMarkerServer and the marker displayed in rviz to contr...
virtual std::string getInfo()
double preset_percent_to_radians_
~qbMoveHW() override
Do nothing.
void setMarkerState(const std::vector< double > &joint_positions)
Update the stored joint positions with the given values.
void read(const ros::Time &time, const ros::Duration &period) override
Call the base method and nothing more.
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
qb_move_interactive_interface::qbMoveInteractive interactive_interface_
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Call the base method and nothing more.
qb_device_hardware_interface::qbDeviceResources device_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void write(const ros::Time &time, const ros::Duration &period) override
The qbrobotics qbmove HardWare interface implements the specific structures to manage the communicati...
std::vector< std::string > names
qb_device_transmission_interface::qbDeviceTransmissionResources transmission_
std::string getDeviceNamespace()
PLUGINLIB_EXPORT_CLASS(transmission_interface::BiDirectionalEffortJointInterfaceProvider, transmission_interface::RequisiteProvider)
bool use_interactive_markers_
void updateShaftPositionLimits()
Update the shaft joint limits since they depend on the fixed motors limits and on the variable stiffn...
std::vector< joint_limits_interface::JointLimits > limits
The qbrobotics qbmove Transmission interface implements the specific transmission_interface::Transmis...
void read(const ros::Time &time, const ros::Duration &period) override