MP-400 Basic Bringup
Launch File
Start the robot by launching the bringup file:
roslaunch neo_mp_400 bringup.launch
Graph
Coming Soon
Nodes
The list of nodes available after the launch of MP-400 bringup file:
Nodes |
|
|
1. neo_kinematics_differential_node |
Node for differential kinematics to calculate motor commands and wheel encoder odometry. |
|
2. neo_teleop_node |
Converts RAW signal from hardware joystick to movement commands. |
|
3. relayboard_v2_node |
Main interface to most internal hardware components. |
|
4. sick_s300_front |
Publishes the measurement data of Sick S300 laserscan. |
|
5. sick_s300_front_filter |
Reduces the measurement data of laserscan to valid region. |
|
6. robot_state_publisher |
Publish the state of the robot to tf. |
|
7. joint_state_publisher |
Publishes Joint state message of the joints involved. |
Interaction and Usage
Motion Control
MP-400 can be controlled by:
1. Publishing data to topic /cmd_vel
2. Control with hardware joystick
Odometry
The odometry from wheelencoders is published by neo_kinematics_differential_node to /odom as nav_msgs/Odometry.
Laser Scanners
1. Front Laser Scanner (sick_s300_front)
Node sick_s300_front publishes laser scan data over the topic /sick_s300_front/scan which is subscribed by the node sick_s300_front_filter and this node publishes filtered scan (minimizing the each scan angle to 170 degrees). Filtered scan data is sent over the topic /sick_s300_front/scan_filtered.
Relayboard
Neobotix Relayboard is the main interface to most internal hardware components.
Connected hardware components:
- Motor controller (left wheel)
- Motor controller (right wheel)
- LCD
- Keypad
- IOBoard (only if available)
- USBoard (only if available)
Published Data
1. Hardware state
See RelayBoardV2.msg.
2. Battery information
See BatteryState.msg.
3. Emergency information
4. IOBoard Data (only if available)
See IOBoard.msg.
5. USBoard Data (only if available)
See USBoard.msg and sensor_msgs/Range.msg.
Services
1. Start automatic charging
rosservice call /relayboard_v2/start_charging
2. Stop automatic charging
rosservice call /relayboard_v2/stop_charging
3. Write text to LCD (maximum 20 characters)
rosservice call /relayboard_v2/set_LCD_msg
4. Toggle relay
rosservice call /relayboard_v2/set_relay