Fake_interface

This package provides fakes hardware interface when the robot is used in simulation.

Fake interface node

The ROS Node is made to simulate:
  • tools interface
  • Conveyor Belt interface
  • joints interface

Published topics - fake interface

Fake Interface’s Published Topics
Name Message Type Description
/niryo_robot/learning_mode/state std_msgs/Bool Learning mode state
/niryo_robot_hardware/tools/current_id std_msgs/Int32 Current tool ID

Services - fake interface

Fake Interface Package Services
Name Message Type Description
/niryo_robot/joints_interface/calibrate_motors SetInt Start motors calibration - value can be 1 for auto calibration, 2 for manual
/niryo_robot/joints_interface/request_new_calibration Trigger Unset motors calibration
niryo_robot/learning_mode/activate Trigger Either activate or deactivate learning mode
niryo_robot/tools/ping_and_set_dxl_tool tools_interface/PingDxlTool Scan and set for a tool plugged
niryo_robot/tools/open_gripper tools_interface/OpenGripper Open a Gripper tool
niryo_robot/tools/close_gripper tools_interface/CloseGripper Close a Gripper tool
niryo_robot/tools/pull_air_vacuum_pump tools_interface/PullAirVacuumPump Pull Vacuum Pump tool
niryo_robot/tools/push_air_vacuum_pump tools_interface/PushAirVacuumPump Push Vacuum Pump tool
/niryo_robot/conveyor/control_conveyor ControlConveyor Send a command to the desired Conveyor Belt
/niryo_robot/conveyor/ping_and_set_conveyor SetConveyor Scan and set a new Conveyor Belt