= MP-500 Basic Bringup =

||||<style="text-align:center">[[http://www.neobotix-robots.com/mobile-robot-%20mp-500.html|{{http://www.neobotix-roboter.de/fileadmin/files/produkte/Basisplattformen/MP-500/Roboter-MP-500-Hauptansicht.jpg|http://www.neobotix-robots.com/mobile-robot-mp-500.html|width="240"}}]] ||

 <<TOC(4)>>

----

== Launch File ==
Start the robot by launching the bringup file:

{{{
roslaunch neo_mp_500 bringup.launch
}}}

----

== Graph ==

'''Coming Soon'''

----

== Nodes ==
The list of nodes available after the launch of MP-500 bringup file:
||<tablewidth="744px" tableheight="386px">'''Nodes''' || ||
||1. neo_kinematics_differential_node || Node for differential kinematics to calculate motor commands and wheel encoder odometry. || [[http://www.ros.org|documentation]] ||
||2. neo_teleop_node ||Converts RAW signal from hardware joystick to movement commands. || [[http://www.ros.org|documentation]] ||
||3. relayboard_v2_node ||Main interface to most internal hardware components. || [[http://www.ros.org|documentation]] ||
||4. sick_s300_front ||Publishes the measurement data of Sick S300 laserscan. || [[http://www.ros.org|documentation]] ||
||5. sick_s300_front_filter ||Reduces the measurement data of laserscan to valid region. || [[http://www.ros.org|documentation]] ||
||6. robot_state_publisher ||Publish the state of the robot to tf. || [[http://www.ros.org|documentation]] ||
||7. joint_state_publisher ||Publishes Joint state message of the joints involved. || [[http://www.ros.org|documentation]] ||

----

== Interaction and Usage ==

=== Motion Control ===
MP-500 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 [[https://github.com/neobotix/neo_msgs/blob/master/msg/RelayBoardV2.msg|RelayBoardV2.msg]].

2. Battery information

See [[http://docs.ros.org/melodic/api/sensor_msgs/html/msg/BatteryState.html|BatteryState.msg]].

3. Emergency information

See [[https://github.com/neobotix/neo_msgs/blob/master/msg/EmergencyStopState.msg|EmergencyStopState.msg]].

4. IOBoard Data (only if available)

See [[https://github.com/neobotix/neo_msgs/blob/master/msg/IOBoard.msg|IOBoard.msg]].

5. USBoard Data (only if available)

See [[https://github.com/neobotix/neo_msgs/blob/master/msg/USBoard.msg|USBoard.msg]] and [[http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Range.html|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
}}}