Skip to content

Common Services - Details

/scale_speed

Type: robot_movement_interface::setFloat.srv

This service scales the maximum speed of the robot in percentage. For example this function can be called to reduce the overall speed to 50%.

rosservice call /scale_speed "value: 0.5"

Parameters:

float32 value: The value to scale the speed with. It can be set to a number between 0.0 and 1.0. A value smaller than 0.0 will be cropped to 0.01 and a value greater than 1.0 will be cropped to 1.0. When the value is set to 0.0 the robot will stop and cancel the movement commands.

Returns: nothing

Note: Some robots might stop their current movement to standstill, before accelerating again and continuing the movement with the new speed.

/get_io

Type: robot_movement_interface::getIO.srv

This service reads the value of a digital i/o port and returns it to the user. For example this function can be called to get the value of port 5.

rosservice call /get_io "number: 5"

Parameters:

int32 number is the digital i/o port to get the value for. Valid port numbers depend on the number of ports provided by the driver.

Returns: bool value: The value of the respective port, if no error occurred. int32 error: Error number: - 0 no error occured - 1 invalid port number

Note: Calling this service during robot movement might stop the movement and cancel the movement commands.

/set_io

Type: robot_movement_interface::setIO.srv

This service sets the value of a digital i/o port. For example this function can be called to set the value of port 5 to true.

rosservice call /set_io "number: 5
value: true"

Parameters:

int32 number is the digital i/o port to set the value for. Valid port numbers depend on the number and type of ports provided by the driver. bool value: The value to set the port to.

Returns: int32 error: Error number: - 0 no error occurred - 1 invalid port number - 2 attempted to set an input port

Note: Calling this service during robot movement might stop the movement and cancel the movement commands.

/stop_robot_right_now

Type: std_srvs::Trigger.srv

This service lets the robot stop moving immediately and cancels the following movement commands.

rosservice call /stop_robot_right_now

Parameters:

none

Returns: bool success: true on successful stopping of the robot movement, false otherwise string message: informational, e.g. for error messages

Note: see also std_srvs::Trigger.srv

/clear_robot_error [optional]

Type: std_srvs::Trigger.srv

This service clears the current controller error, in a similar way as clicking in the teach pendant.

rosservice call /clear_robot_error

Parameters:

none

Returns: bool success: true on successful repairing the current controller error, false otherwise string message: informational, e.g. for error messages

Note: This service is optional. see also std_srvs::Trigger.srv