rostopic

Button

  1. Plus(+) button

    $ rostopic echo -c /cobotta/plus_button
    
  2. Minus(-) button

    $ rostopic echo -c /cobotta/minus_button
    
  3. Function button

    $ rostopic echo -c /cobotta/function_button
    

MiniIO

data: Hex Description
0 0x0000 all bits are OFF
1 0x0001 bit0 is ON
32768 0x8000 bit15 is ON
65535 0xffff all bits are ON
  1. Get the Mini IO data

    $ rostopic echo -c /cobotta/miniIO_input
    
  2. Set the Mini IO data

    $ rostopic pub /cobotta/miniIO_output std_msgs/UInt16 "data: 0"
    

Tip

For more information about I/O allocation, please refer to COBOTTA user manual ID:7261.

Robot state

$ rostopic echo -c /cobotta/robot_state

Safety MCU state

$ rostopic echo -c /cobotta/safe_state

Parallel gripper

target_position[m] speed[%] effort[n]
0.0 - 0.015 1.0 - 100.0 6.0 - 20.0

Attention

target_position is changed on 1.2.2. Before 1.2.1, target_position range is 0.0 - 0.03.

  1. Parallel gripper open

    $ rostopic pub /cobotta/gripper_move/goal \
        denso_cobotta_gripper/GripperMoveActionGoal \
          "{header: {seq: 0, stamp: {secs: 0, nsecs: 0}, frame_id: ''}, \
            goal_id: { stamp: { secs: 0, nsecs: 0}}, \
            goal: {target_position: 0.015, speed: 10.0, effort: 10.0}}"
    
  2. Parallel gripper close

    $ rostopic pub /cobotta/gripper_move/goal \
        denso_cobotta_gripper/GripperMoveActionGoal \
          "{header: {seq: 0, stamp: {secs: 0, nsecs: 0}, frame_id: ''}, \
            goal_id: { stamp: { secs: 0, nsecs: 0}}, \
            goal: {target_position: 0.0, speed: 5.0, effort: 10.0}}"
    

Vacuum gripper

Description direction: power_percentage[%]
Suction -1 40 - 100
Stop 0
Blow 1
  1. Suction

    $ rostopic pub /cobotta/vacuum_move/goal \
        denso_cobotta_gripper/VacuumMoveActionGoal \
          "{header:  {seq: 0, stamp: {secs: 0, nsecs: 0},  frame_id: ''}, \
             goal_id: { stamp: { secs: 0, nsecs: 0}}, \
             goal: {direction: 1, power_percentage: 40.0}}"
    
  2. Stop

    $ rostopic pub /cobotta/vacuum_move/goal \
        denso_cobotta_gripper/VacuumMoveActionGoal \
          "{header:  {seq: 0, stamp: {secs: 0, nsecs: 0},  frame_id: ''}, \
             goal_id: { stamp: { secs: 0, nsecs: 0}}, \
             goal: {direction: 0, power_percentage: 40.0}}"