sr_robot_msgs

Summary

sr_robot_msgs
Version:

1.4.0

Description:

sr_robot_msgs contains some messages used in the shadow_robot stack.

Maintainers:
  • Shadow Robot’s software team <software AT shadowrobot DOT com>
Licenses:
  • GPL
Urls:
Authors:
  • Ugo Cupcic
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

sr_robot_msgs/UBI0
Field:
  • distal[12] (uint16) –
uint16[12] distal
sr_robot_msgs/ShadowContactStateStamped
Field:

All 3D vectors are referenced in the fingertip core center

# All 3D vectors are referenced in the fingertip core center

Header header					# stamp
geometry_msgs/Vector3 tangential_force  	# tangential force (local shear force)
geometry_msgs/Point  contact_position		# contact position
geometry_msgs/Vector3 contact_normal      	# contact normal
float64 Fnormal					# amplitude of normal force (along normal)
float64 Ltorque					# amplitude of local torque (around normal)
sr_robot_msgs/JointControllerState
Field:
  • header (std_msgs/Header) –
  • set_point (float64) –
  • process_value (float64) –
  • process_value_dot (float64) –
  • commanded_velocity (float64) –
  • error (float64) –
  • time_step (float64) –
  • command (float64) –
  • measured_effort (float64) –
  • friction_compensation (float64) –
  • position_p (float64) –
  • position_i (float64) –
  • position_d (float64) –
  • position_i_clamp (float64) –
  • velocity_p (float64) –
  • velocity_i (float64) –
  • velocity_d (float64) –
  • velocity_i_clamp (float64) –
Header header
float64 set_point
float64 process_value
float64 process_value_dot
float64 commanded_velocity
float64 error
float64 time_step
float64 command
float64 measured_effort
float64 friction_compensation
float64 position_p
float64 position_i
float64 position_d
float64 position_i_clamp
float64 velocity_p
float64 velocity_i
float64 velocity_d
float64 velocity_i_clamp
sr_robot_msgs/FromMotorDataType
Field:
  • data (int16) –
int16 data
sr_robot_msgs/JointMusclePositionControllerState
Field:
  • header (std_msgs/Header) –
  • set_point (float64) –
  • process_value (float64) –
  • process_value_dot (float64) –
  • error (float64) –
  • time_step (float64) –
  • pseudo_command (float64) –
  • valve_muscle_0 (int8) –
  • valve_muscle_1 (int8) –
  • packed_valve (float64) –
  • muscle_pressure_0 (uint16) –
  • muscle_pressure_1 (uint16) –
  • p (float64) –
  • i (float64) –
  • d (float64) –
  • i_clamp (float64) –
Header header
float64 set_point
float64 process_value
float64 process_value_dot
float64 error
float64 time_step
float64 pseudo_command
int8 valve_muscle_0
int8 valve_muscle_1
float64 packed_valve
uint16 muscle_pressure_0
uint16 muscle_pressure_1
float64 p
float64 i
float64 d
float64 i_clamp
sr_robot_msgs/sendupdate
Field:
int8 sendupdate_length
joint[] sendupdate_list
sr_robot_msgs/MotorSystemControls
Field:
  • motor_id (int8) –
  • enable_backlash_compensation (bool) –
  • increase_sgl_tracking (bool) –
  • decrease_sgl_tracking (bool) –
  • increase_sgr_tracking (bool) –
  • decrease_sgr_tracking (bool) –
  • initiate_jiggling (bool) –
  • write_config_to_eeprom (bool) –
int8 motor_id                     # the id of the motor you want to control

bool enable_backlash_compensation # switch on/off backlash compensation at the motor level
bool increase_sgl_tracking        # increment the tracking value for the left gauge
bool decrease_sgl_tracking        # decrement the tracking value for the left gauge
bool increase_sgr_tracking        # increment the tracking value for the right gauge
bool decrease_sgr_tracking        # decrement the tracking value for the right gauge
bool initiate_jiggling            # starts jiggling the given motor
bool write_config_to_eeprom       # write the current configuration to the eeprom
sr_robot_msgs/GraspArray
Field:

An array of moveit grasps. Useful for serialisation.

# An array of moveit grasps. Useful for serialisation.
moveit_msgs/Grasp[] grasps
sr_robot_msgs/config
Field:
  • node_name (string) –
  • list_of_parameters[] (string) –
  • length_of_list (uint8) –

modify the config of a node e.g. change the transmission rate

# modify the config of a node
# e.g. change the transmission rate
string   node_name
string[] list_of_parameters
uint8    length_of_list
sr_robot_msgs/cartesian_data
Field:
int8                 cartesian_positions_length
cartesian_position[] cartesian_positions
sr_robot_msgs/joint
Field:
  • joint_name (string) –
  • joint_position (float64) –
  • joint_target (float64) –
  • joint_torque (float64) –
  • joint_temperature (float64) –
  • joint_current (float64) –
  • error_flag (string) –
string  joint_name
float64 joint_position
float64 joint_target
float64 joint_torque
float64 joint_temperature
float64 joint_current
string  error_flag
sr_robot_msgs/JointMuscleValveControllerState
Field:
  • header (std_msgs/Header) –
  • set_valve_muscle_0 (int8) –
  • set_valve_muscle_1 (int8) –
  • set_duration_muscle_0 (uint64) –
  • set_duration_muscle_1 (uint64) –
  • current_valve_muscle_0 (int8) –
  • current_valve_muscle_1 (int8) –
  • current_duration_muscle_0 (uint64) –
  • current_duration_muscle_1 (uint64) –
  • packed_valve (float64) –
  • muscle_pressure_0 (uint16) –
  • muscle_pressure_1 (uint16) –
  • time_step (float64) –
Header header
int8 set_valve_muscle_0
int8 set_valve_muscle_1
uint64 set_duration_muscle_0
uint64 set_duration_muscle_1
int8 current_valve_muscle_0
int8 current_valve_muscle_1
uint64 current_duration_muscle_0
uint64 current_duration_muscle_1
float64 packed_valve
uint16 muscle_pressure_0
uint16 muscle_pressure_1
float64 time_step
sr_robot_msgs/AuxSpiData
Field:
Header header
uint16[16] sensors
sr_robot_msgs/reverseKinematics
Field:
  • finger_name (string) –
string  finger_name
sr_robot_msgs/ShadowPST
Field:
  • header (std_msgs/Header) –
  • pressure[] (int16) –
  • temperature[] (int16) –
Header header
int16[] pressure
int16[] temperature
sr_robot_msgs/Tactile
Field:
std_msgs/Int16[] data
sr_robot_msgs/cartesian_position
Field:
  • tip_name (string) –
  • tip_pos_x (float32) –
  • tip_pos_y (float32) –
  • tip_pos_z (float32) –
  • tip_orientation_rho (float32) –
  • tip_orientation_theta (float32) –
  • tip_orientation_sigma (float32) –
string  tip_name
float32 tip_pos_x
float32 tip_pos_y
float32 tip_pos_z
float32 tip_orientation_rho
float32 tip_orientation_theta
float32 tip_orientation_sigma
sr_robot_msgs/UBI0All
Field:
Header header
UBI0[5] tactiles
sr_robot_msgs/command
Field:

sendupdate is 1 contrlr is 2

# sendupdate is 1
# contrlr is 2
int8 command_type

sendupdate sendupdate_command
contrlr contrlr_command
sr_robot_msgs/Biotac
Field:
  • pac0 (int16) –
  • pac1 (int16) –
  • pdc (int16) –
  • tac (int16) –
  • tdc (int16) –
  • electrodes[19] (int16) –
int16 pac0
int16 pac1
int16 pdc

int16 tac
int16 tdc

int16[19] electrodes
sr_robot_msgs/BiotacAll
Field:
Header header
Biotac[5] tactiles
sr_robot_msgs/contrlr
Field:
  • contrlr_name (string) –
  • list_of_parameters[] (string) –
  • length_of_list (uint8) –

the contrlr name (e.g. smart_motor_ff2)

# the contrlr name (e.g. smart_motor_ff2)
string   contrlr_name

# specify here a list of parameter_name:value
# e.g. p:10 sets the p value of the controller to 10
# the possible parameters are:
#int16  p
#int16  i
#int16  d
#int16  imax
#int16  target
#int16  sensor
#int16  valve 
#int16  deadband
#int16  offset
#int16  shift
#int16  max
#
## parameters for the motors
#int16  motor_maxforce
#int16  motor_safeforce
#int16  force_p
#int16  force_i
#int16  force_d
#int16  force_imax
#int16  force_out_shift
#int16  force_deadband
#int16  force_offset
#int16  sensor_imax
#int16  sensor_deadband
#int16  sensor_offset
#int16  max_temperature
#int16  max_current

string[] list_of_parameters

# the size of the list_of_parameters you are sending
uint8 	 length_of_list
sr_robot_msgs/MidProxDataAll
Field:
Header header
MidProxData[5] sensors
sr_robot_msgs/MidProxData
Field:
  • middle[4] (uint16) –
  • proximal[4] (uint16) –
uint16[4] middle
uint16[4] proximal
sr_robot_msgs/ControlType
Field:
  • control_type (int16) –
Constant:
  • PWM (int16):0
  • FORCE (int16):1
  • QUERY (int16):-1
int16 control_type

int16 PWM=0
int16 FORCE=1

#used to query which control type we're using. won't change the control type
int16 QUERY=-1
sr_robot_msgs/joints_data
Field:
int8 joints_list_length
joint[] joints_list
sr_robot_msgs/JointMuscleValveControllerCommand
Field:
  • cmd_valve_muscle[2] (int8) –
  • cmd_duration_ms[2] (uint64) –

This command will allow the user to specify a separate command for each of the two muscles that control the joint. The user will also specify a duration in ms for that command. During this duration the command will be sent to the hand every ms. Once this duration period has elapsed, a command of 0 will be sent to the muscle (meaning both the filling and emptying valves for that muscle remain closed), until a new command is received A duration of 0 means that there is no timeout, so the valve command will be sent to the muscle until a different valve command is received. BE CAREFUL WHEN USING A DURATION OF 0 AS THIS COULD EVENTUALLY DAMAGE THE MUSCLE

Allowed values for the cmd_valve_muscle are integers from -4 to +4. +4 the filling valve is open during a full ms cycle. Emptying valve is closed +3 the filling valve is open during 0.75 ms and closed during 0.25 ms in a 1 ms cycle. Emptying valve is closed +2 the filling valve is open during 0.5 ms and closed during 0.5 ms in a 1 ms cycle. Emptying valve is closed +1 the filling valve is open during 0.25 ms and closed during 0.75 ms in a 1 ms cycle. Emptying valve is closed 0 both valves (filling and emptying) remain closed in a 1 ms cycle ... -3 the emptying valve is open during 0.75 ms and closed during 0.25 ms in a 1 ms cycle. Filling valve is closed -4 the emptying valve is open during a full ms cycle. Filling valve is closed

# This command will allow the user to specify a separate command for each of the two muscles that control the joint.
# The user will also specify a duration in ms for that command. During this duration the command will be sent to the hand
# every ms. 
# Once this duration period has elapsed, a command of 0 will be sent to the muscle (meaning both the filling and emptying valves for that 
# muscle remain closed), until a new command is received
# A duration of 0 means that there is no timeout, so the valve command will be sent to the muscle until a different valve command is received.
# BE CAREFUL WHEN USING A DURATION OF 0 AS THIS COULD EVENTUALLY DAMAGE THE MUSCLE

# Allowed values for the cmd_valve_muscle are integers from -4 to +4.
# +4 the filling valve is open during a full ms cycle. Emptying valve is closed
# +3 the filling valve is open during 0.75 ms and closed during 0.25 ms in a 1 ms cycle. Emptying valve is closed
# +2 the filling valve is open during 0.5 ms and closed during 0.5 ms in a 1 ms cycle. Emptying valve is closed
# +1 the filling valve is open during 0.25 ms and closed during 0.75 ms in a 1 ms cycle. Emptying valve is closed
# 0 both valves (filling and emptying) remain closed in a 1 ms cycle
# ...
# -3 the emptying valve is open during 0.75 ms and closed during 0.25 ms in a 1 ms cycle. Filling valve is closed
# -4 the emptying valve is open during a full ms cycle. Filling valve is closed

int8[2] cmd_valve_muscle
uint64[2] cmd_duration_ms
sr_robot_msgs/EthercatDebug
Field:
  • header (std_msgs/Header) –
  • sensors[] (int16) –
  • motor_data_type (sr_robot_msgs/FromMotorDataType) –
  • which_motors (int16) –
  • which_motor_data_arrived (int32) –
  • which_motor_data_had_errors (int32) –
  • motor_data_packet_torque[] (int16) –
  • motor_data_packet_misc[] (int16) –
  • tactile_data_type (int32) –
  • tactile_data_valid (int16) –
  • tactile[] (int16) –
  • idle_time_us (int16) –
Header               header

int16[]              sensors
FromMotorDataType    motor_data_type
int16                which_motors
int32                which_motor_data_arrived
int32                which_motor_data_had_errors
int16[]              motor_data_packet_torque
int16[]              motor_data_packet_misc
int32                tactile_data_type
int16                tactile_data_valid
int16[]              tactile
int16                idle_time_us
sr_robot_msgs/TactileArray
Field:
Header header
Tactile[] data

Service types

sr_robot_msgs/SetEffortControllerGains
Field (Request):
 
  • max_force (float64) –
  • friction_deadband (int32) –
float64 max_force
int32 friction_deadband
---
sr_robot_msgs/SetPidGains
Field (Request):
 
  • p (float64) –
  • i (float64) –
  • d (float64) –
  • i_clamp (float64) –
  • max_force (float64) –
  • deadband (float64) –
  • friction_deadband (int32) –
float64 p
float64 i
float64 d
float64 i_clamp
float64 max_force
float64 deadband
int32 friction_deadband
---
sr_robot_msgs/ChangeControlType
Field (Request):
 
Field (Response):
 
ControlType control_type
---
ControlType result
sr_robot_msgs/ChangeMotorSystemControls
Field (Request):
 
Field (Response):
 
  • result (int8) –
Constant (Response):
 
  • SUCCESS (int8):0
  • MOTOR_ID_OUT_OF_RANGE (int8):-1
MotorSystemControls[] motor_system_controls
---
int8 result

int8 SUCCESS=0
int8 MOTOR_ID_OUT_OF_RANGE=-1
sr_robot_msgs/SetDebugData
Field (Request):
 
  • motor_index (int16) –
  • motor_data_type (int16) –
  • publisher_index (int16) –
Field (Response):
 
  • success (bool) –

if motor_data_type == -1 -> publish MOTOR_DEMAND_TORQUE if motor_data_type > 0 -> motor_data_type must be in FROM_MOTOR_DATA_TYPE enum

# if motor_data_type == -1 -> publish MOTOR_DEMAND_TORQUE
# if motor_data_type > 0   -> motor_data_type must be in FROM_MOTOR_DATA_TYPE enum


int16 motor_index
int16 motor_data_type
int16 publisher_index
---
bool success
sr_robot_msgs/ManualSelfTest
Field (Request):
 
  • message (string) –
Field (Response):
 
  • ok (bool) –
  • message (string) –
string message
---
bool ok
string message
sr_robot_msgs/SetMixedPositionVelocityPidGains
Field (Request):
 
  • position_p (float64) –
  • position_i (float64) –
  • position_d (float64) –
  • position_i_clamp (float64) –
  • min_velocity (float64) –
  • max_velocity (float64) –
  • position_deadband (float64) –
  • velocity_p (float64) –
  • velocity_i (float64) –
  • velocity_d (float64) –
  • velocity_i_clamp (float64) –
  • max_force (float64) –
  • friction_deadband (int32) –
float64 position_p
float64 position_i
float64 position_d
float64 position_i_clamp
float64 min_velocity
float64 max_velocity
float64 position_deadband

float64 velocity_p
float64 velocity_i
float64 velocity_d
float64 velocity_i_clamp
float64 max_force

int32 friction_deadband
---
sr_robot_msgs/is_hand_occupied
Field (Response):
 
  • hand_occupied (bool) –
---
bool hand_occupied
sr_robot_msgs/NullifyDemand
Field (Request):
 
  • nullify_demand (bool) –
This service is used to nullify the demand of the etherCAT
hand. If the nullify_demand parameter is set to True, the demand sent to the robot will be 0, regardless of the computed effort demanded by the controller.
#This service is used to nullify the demand of the etherCAT
# hand. If the nullify_demand parameter is set to True,
# the demand sent to the robot will be 0, regardless of the
# computed effort demanded by the controller.

bool nullify_demand
---
sr_robot_msgs/which_fingers_are_touching
Field (Request):
 
  • force_thresholds[] (float64) –
Field (Response):
 
  • touch_forces[] (float64) –

takes a vector of 5 doubles as the force thresholds with which a contact is detected. the order is FF; MF; RF; LF; TH

# takes a vector of 5 doubles as the force thresholds
# with which a contact is detected.
# the order is FF; MF; RF; LF; TH

float64[] force_thresholds
---
float64[] touch_forces

# returns a vector of 5 touch forces, containing
# 0 if force < force_threshold, current force
# otherwise
sr_robot_msgs/ForceController
Field (Request):
 
  • maxpwm (int16) –
  • sgleftref (int16) –
  • sgrightref (int16) –
  • f (int16) –
  • p (int16) –
  • i (int16) –
  • d (int16) –
  • imax (int16) –
  • deadband (int16) –
  • sign (int16) –
Field (Response):
 
  • configured (bool) –
int16 maxpwm       # the maximum pwm the motor can apply
int16 sgleftref    # the left strain gauge amp reference
int16 sgrightref   # the right strain gauge amp reference
int16 f            # the feed forward gain value for the force controller
int16 p            # the p value for the force controller
int16 i            # the i value for the force controller
int16 d            # the d value for the force controller
int16 imax         # the imax value for the force controller
int16 deadband     # the deadband value for the force controller
int16 sign         # the sign of the force controller
---
bool configured    # return true if the configuration worked, false otherwise
sr_robot_msgs/GetSegmentedLine
Field (Response):
 
---
sensor_msgs/PointCloud2 line_cloud
sr_robot_msgs/SimpleMotorFlasher
Field (Request):
 
  • firmware (string) –
  • motor_id (int8) –
Field (Response):
 
  • value (int32) –
Constant (Response):
 
  • SUCCESS (int32):0
  • FAIL (int32):1
string firmware
int8 motor_id
---
int32 value
# value must take one of the following values
int32 SUCCESS = 0
int32 FAIL = 1

Action types

sr_robot_msgs/PlanGrasp
Field (Goal):
Field (Result):
Field (Feedback):
 
  • number_of_synthesized_grasps (int32) –

Goal Fill in as much as you know about the object. Different planners will use different information, see their docs.

# Goal
# Fill in as much as you know about the object. Different planners will use
# different information, see their docs.
object_recognition_msgs/RecognizedObject object
---
# Result
moveit_msgs/Grasp[] grasps
---
# Feedback
# Number of grasps synthesized so far.
int32 number_of_synthesized_grasps
sr_robot_msgs/Grasp
Field (Goal):
Constant (Feedback):
 
  • PRE_GRASPING (uint8):0
  • GRASPING (uint8):1
  • RELEASING (uint8):2
Field (Feedback):
 
  • state (uint8) –
  • quality (float64) –

Move hand to pre-grasp pose then grasp pose for the given grasp. When goal is preempted release the grasp by moving back to pre-grasp. Note no object is involved, this is just for testing grasp positions etc. Goal

# Move hand to pre-grasp pose then grasp pose for the given grasp.
# When goal is preempted release the grasp by moving back to pre-grasp.
# Note no object is involved, this is just for testing grasp positions etc.
# Goal
moveit_msgs/Grasp grasp
bool pre_grasp
---
# Result
---
# Feedback
# State shows what the node is currently doing.
uint8 PRE_GRASPING=0
uint8 GRASPING=1
uint8 RELEASING=2
uint8 state
# A percentage or other measure of the quality of the grasp.
float64 quality