ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher

rosserial_mbed Hello World

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}

Files at this revision

API Documentation at this revision

Comitter:
garyservin
Date:
Thu Mar 31 14:22:59 2016 +0000
Commit message:
Initial commit, generated based on a clean indigo-desktop-full

Changed in this revision

BufferedSerial.lib Show annotated file Show diff for this revision Revisions of this file
MbedHardware.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestAction.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestActionGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestActionResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestAction.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestActionGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestActionResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestRequestResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TestResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsAction.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsActionGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsActionResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib/TwoIntsResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib_msgs/GoalID.h Show annotated file Show diff for this revision Revisions of this file
actionlib_msgs/GoalStatus.h Show annotated file Show diff for this revision Revisions of this file
actionlib_msgs/GoalStatusArray.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingAction.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingActionGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingActionResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/AveragingResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciAction.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciActionGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciActionResult.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciFeedback.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciGoal.h Show annotated file Show diff for this revision Revisions of this file
actionlib_tutorials/FibonacciResult.h Show annotated file Show diff for this revision Revisions of this file
bond/Constants.h Show annotated file Show diff for this revision Revisions of this file
bond/Status.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryAction.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryActionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryActionResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/FollowJointTrajectoryResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommand.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandAction.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandActionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandActionResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/GripperCommandResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointControllerState.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTolerance.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryAction.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryActionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryActionResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryControllerState.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/JointTrajectoryResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadAction.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadActionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadActionResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/PointHeadResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/QueryCalibrationState.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/QueryTrajectoryState.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionAction.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionActionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionActionResult.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionFeedback.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionGoal.h Show annotated file Show diff for this revision Revisions of this file
control_msgs/SingleJointPositionResult.h Show annotated file Show diff for this revision Revisions of this file
diagnostic_msgs/DiagnosticArray.h Show annotated file Show diff for this revision Revisions of this file
diagnostic_msgs/DiagnosticStatus.h Show annotated file Show diff for this revision Revisions of this file
diagnostic_msgs/KeyValue.h Show annotated file Show diff for this revision Revisions of this file
diagnostic_msgs/SelfTest.h Show annotated file Show diff for this revision Revisions of this file
driver_base/ConfigString.h Show annotated file Show diff for this revision Revisions of this file
driver_base/ConfigValue.h Show annotated file Show diff for this revision Revisions of this file
driver_base/SensorLevels.h Show annotated file Show diff for this revision Revisions of this file
duration.cpp Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/BoolParameter.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/Config.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/ConfigDescription.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/DoubleParameter.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/Group.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/GroupState.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/IntParameter.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/ParamDescription.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/Reconfigure.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/SensorLevels.h Show annotated file Show diff for this revision Revisions of this file
dynamic_reconfigure/StrParameter.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ApplyBodyWrench.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ApplyJointEffort.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/BodyRequest.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ContactState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ContactsState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/DeleteModel.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetJointProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetLinkProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetLinkState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetModelProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetModelState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetPhysicsProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/GetWorldProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/JointRequest.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/LinkState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/LinkStates.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ModelState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ModelStates.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ODEJointProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/ODEPhysics.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetJointProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetJointTrajectory.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetLinkProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetLinkState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetModelConfiguration.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetModelState.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SetPhysicsProperties.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/SpawnModel.h Show annotated file Show diff for this revision Revisions of this file
gazebo_msgs/WorldState.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Accel.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/AccelStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/AccelWithCovariance.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/AccelWithCovarianceStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Inertia.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/InertiaStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Point.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Point32.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PointStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Polygon.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PolygonStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Pose.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Pose2D.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseArray.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseWithCovariance.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseWithCovarianceStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Quaternion.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/QuaternionStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Transform.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TransformStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Twist.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistWithCovariance.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistWithCovarianceStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Vector3.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Vector3Stamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Wrench.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/WrenchStamped.h Show annotated file Show diff for this revision Revisions of this file
laser_assembler/AssembleScans.h Show annotated file Show diff for this revision Revisions of this file
laser_assembler/AssembleScans2.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/GetMapROI.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/GetPointMap.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/GetPointMapROI.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/OccupancyGridUpdate.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/PointCloud2Update.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/ProjectedMap.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/ProjectedMapInfo.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/ProjectedMapsInfo.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/SaveMap.h Show annotated file Show diff for this revision Revisions of this file
map_msgs/SetMapProjections.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMap.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapAction.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapActionGoal.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapActionResult.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapFeedback.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapGoal.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMapResult.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetPlan.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GridCells.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/MapMetaData.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/OccupancyGrid.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Odometry.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Path.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/SetMap.h Show annotated file Show diff for this revision Revisions of this file
nodelet/NodeletList.h Show annotated file Show diff for this revision Revisions of this file
nodelet/NodeletLoad.h Show annotated file Show diff for this revision Revisions of this file
nodelet/NodeletUnload.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Circle.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/CircleArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/CircleArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Contour.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/ContourArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/ContourArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Face.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/FaceArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/FaceArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Flow.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/FlowArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/FlowArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/FlowStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Line.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/LineArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/LineArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Moment.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/MomentArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/MomentArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Point2D.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Point2DArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Point2DArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Point2DStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Rect.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RectArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RectArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RotatedRect.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RotatedRectArray.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RotatedRectArrayStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/RotatedRectStamped.h Show annotated file Show diff for this revision Revisions of this file
opencv_apps/Size.h Show annotated file Show diff for this revision Revisions of this file
pcl_msgs/ModelCoefficients.h Show annotated file Show diff for this revision Revisions of this file
pcl_msgs/PointIndices.h Show annotated file Show diff for this revision Revisions of this file
pcl_msgs/PolygonMesh.h Show annotated file Show diff for this revision Revisions of this file
pcl_msgs/Vertices.h Show annotated file Show diff for this revision Revisions of this file
polled_camera/GetPolledImage.h Show annotated file Show diff for this revision Revisions of this file
ros.h Show annotated file Show diff for this revision Revisions of this file
ros/duration.h Show annotated file Show diff for this revision Revisions of this file
ros/msg.h Show annotated file Show diff for this revision Revisions of this file
ros/node_handle.h Show annotated file Show diff for this revision Revisions of this file
ros/publisher.h Show annotated file Show diff for this revision Revisions of this file
ros/service_client.h Show annotated file Show diff for this revision Revisions of this file
ros/service_server.h Show annotated file Show diff for this revision Revisions of this file
ros/subscriber.h Show annotated file Show diff for this revision Revisions of this file
ros/time.h Show annotated file Show diff for this revision Revisions of this file
roscpp/Empty.h Show annotated file Show diff for this revision Revisions of this file
roscpp/GetLoggers.h Show annotated file Show diff for this revision Revisions of this file
roscpp/Logger.h Show annotated file Show diff for this revision Revisions of this file
roscpp/SetLoggerLevel.h Show annotated file Show diff for this revision Revisions of this file
roscpp_tutorials/TwoInts.h Show annotated file Show diff for this revision Revisions of this file
rosgraph_msgs/Clock.h Show annotated file Show diff for this revision Revisions of this file
rosgraph_msgs/Log.h Show annotated file Show diff for this revision Revisions of this file
rosgraph_msgs/TopicStatistics.h Show annotated file Show diff for this revision Revisions of this file
rospy_tutorials/AddTwoInts.h Show annotated file Show diff for this revision Revisions of this file
rospy_tutorials/BadTwoInts.h Show annotated file Show diff for this revision Revisions of this file
rospy_tutorials/Floats.h Show annotated file Show diff for this revision Revisions of this file
rospy_tutorials/HeaderString.h Show annotated file Show diff for this revision Revisions of this file
rosserial_mbed/Adc.h Show annotated file Show diff for this revision Revisions of this file
rosserial_mbed/Test.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/Log.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/RequestMessageInfo.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/RequestParam.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/RequestServiceInfo.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/TopicInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CameraInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/ChannelFloat32.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CompressedImage.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/FluidPressure.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Illuminance.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Image.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Imu.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/JointState.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Joy.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/JoyFeedback.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/JoyFeedbackArray.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/LaserEcho.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/LaserScan.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/MagneticField.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/MultiDOFJointState.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/MultiEchoLaserScan.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatFix.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatStatus.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud2.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointField.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Range.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/RegionOfInterest.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/RelativeHumidity.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/SetCameraInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Temperature.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/TimeReference.h Show annotated file Show diff for this revision Revisions of this file
shape_msgs/Mesh.h Show annotated file Show diff for this revision Revisions of this file
shape_msgs/MeshTriangle.h Show annotated file Show diff for this revision Revisions of this file
shape_msgs/Plane.h Show annotated file Show diff for this revision Revisions of this file
shape_msgs/SolidPrimitive.h Show annotated file Show diff for this revision Revisions of this file
smach_msgs/SmachContainerInitialStatusCmd.h Show annotated file Show diff for this revision Revisions of this file
smach_msgs/SmachContainerStatus.h Show annotated file Show diff for this revision Revisions of this file
smach_msgs/SmachContainerStructure.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Bool.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Byte.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ByteMultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Char.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ColorRGBA.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Duration.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Empty.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Header.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayDimension.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayLayout.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/String.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Time.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_srvs/Empty.h Show annotated file Show diff for this revision Revisions of this file
std_srvs/Trigger.h Show annotated file Show diff for this revision Revisions of this file
stereo_msgs/DisparityImage.h Show annotated file Show diff for this revision Revisions of this file
tf/FrameGraph.h Show annotated file Show diff for this revision Revisions of this file
tf/tf.h Show annotated file Show diff for this revision Revisions of this file
tf/tfMessage.h Show annotated file Show diff for this revision Revisions of this file
tf/transform_broadcaster.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/FrameGraph.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformAction.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformActionGoal.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformActionResult.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformFeedback.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformGoal.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/LookupTransformResult.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/TF2Error.h Show annotated file Show diff for this revision Revisions of this file
tf2_msgs/TFMessage.h Show annotated file Show diff for this revision Revisions of this file
theora_image_transport/Packet.h Show annotated file Show diff for this revision Revisions of this file
time.cpp Show annotated file Show diff for this revision Revisions of this file
topic_tools/DemuxAdd.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/DemuxDelete.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/DemuxList.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/DemuxSelect.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxAdd.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxDelete.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxList.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxSelect.h Show annotated file Show diff for this revision Revisions of this file
trajectory_msgs/JointTrajectory.h Show annotated file Show diff for this revision Revisions of this file
trajectory_msgs/JointTrajectoryPoint.h Show annotated file Show diff for this revision Revisions of this file
trajectory_msgs/MultiDOFJointTrajectory.h Show annotated file Show diff for this revision Revisions of this file
trajectory_msgs/MultiDOFJointTrajectoryPoint.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeAction.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeActionFeedback.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeActionGoal.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeActionResult.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeFeedback.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeGoal.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/ShapeResult.h Show annotated file Show diff for this revision Revisions of this file
turtle_actionlib/Velocity.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/Color.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/Kill.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/Pose.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/SetPen.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/Spawn.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/TeleportAbsolute.h Show annotated file Show diff for this revision Revisions of this file
turtlesim/TeleportRelative.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/ImageMarker.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarker.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarkerControl.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarkerFeedback.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarkerInit.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarkerPose.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/InteractiveMarkerUpdate.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/Marker.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/MarkerArray.h Show annotated file Show diff for this revision Revisions of this file
visualization_msgs/MenuEntry.h Show annotated file Show diff for this revision Revisions of this file
diff -r 000000000000 -r fd24f7ca9688 BufferedSerial.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/BufferedSerial.lib	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/sam_grove/code/BufferedSerial/#a0d37088b405
diff -r 000000000000 -r fd24f7ca9688 MbedHardware.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MbedHardware.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,60 @@
+/*
+ * MbedHardware
+ *
+ *  Created on: Aug 17, 2011
+ *      Author: nucho
+ */
+
+#ifndef ROS_MBED_HARDWARE_H_
+#define ROS_MBED_HARDWARE_H_
+
+#include "mbed.h"
+
+#include "BufferedSerial.h"
+
+class MbedHardware {
+  public:
+    MbedHardware(PinName tx, PinName rx, long baud = 57600)
+      :iostream(tx, rx){
+      baud_ = baud;
+      t.start();
+    }
+
+    MbedHardware()
+      :iostream(USBTX, USBRX) {
+        baud_ = 57600;
+        t.start();
+    }
+
+    void setBaud(long baud){
+      this->baud_= baud;
+    }
+
+    int getBaud(){return baud_;}
+
+    void init(){
+        iostream.baud(baud_);
+    }
+
+    int read(){
+        if (iostream.readable()) {
+            return iostream.getc();
+        } else {
+            return -1;
+        }
+    };
+    void write(uint8_t* data, int length) {
+        for (int i=0; i<length; i++)
+             iostream.putc(data[i]);
+    }
+
+    unsigned long time(){return t.read_ms();}
+
+protected:
+    BufferedSerial iostream;
+    long baud_;
+    Timer t;
+};
+
+
+#endif /* ROS_MBED_HARDWARE_H_ */
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestAction_h
+#define _ROS_actionlib_TestAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib/TestActionGoal.h"
+#include "actionlib/TestActionResult.h"
+#include "actionlib/TestActionFeedback.h"
+
+namespace actionlib
+{
+
+  class TestAction : public ros::Msg
+  {
+    public:
+      actionlib::TestActionGoal action_goal;
+      actionlib::TestActionResult action_result;
+      actionlib::TestActionFeedback action_feedback;
+
+    TestAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestAction"; };
+    const char * getMD5(){ return "991e87a72802262dfbe5d1b3cf6efc9a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestActionFeedback_h
+#define _ROS_actionlib_TestActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TestFeedback.h"
+
+namespace actionlib
+{
+
+  class TestActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TestFeedback feedback;
+
+    TestActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestActionFeedback"; };
+    const char * getMD5(){ return "6d3d0bf7fb3dda24779c010a9f3eb7cb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestActionGoal_h
+#define _ROS_actionlib_TestActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib/TestGoal.h"
+
+namespace actionlib
+{
+
+  class TestActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      actionlib::TestGoal goal;
+
+    TestActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestActionGoal"; };
+    const char * getMD5(){ return "348369c5b403676156094e8c159720bf"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestActionResult_h
+#define _ROS_actionlib_TestActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TestResult.h"
+
+namespace actionlib
+{
+
+  class TestActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TestResult result;
+
+    TestActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestActionResult"; };
+    const char * getMD5(){ return "3d669e3a63aa986c667ea7b0f46ce85e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_actionlib_TestFeedback_h
+#define _ROS_actionlib_TestFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TestFeedback : public ros::Msg
+  {
+    public:
+      int32_t feedback;
+
+    TestFeedback():
+      feedback(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_feedback;
+      u_feedback.real = this->feedback;
+      *(outbuffer + offset + 0) = (u_feedback.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_feedback.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_feedback.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_feedback.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->feedback);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_feedback;
+      u_feedback.base = 0;
+      u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->feedback = u_feedback.real;
+      offset += sizeof(this->feedback);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestFeedback"; };
+    const char * getMD5(){ return "49ceb5b32ea3af22073ede4a0328249e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_actionlib_TestGoal_h
+#define _ROS_actionlib_TestGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TestGoal : public ros::Msg
+  {
+    public:
+      int32_t goal;
+
+    TestGoal():
+      goal(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_goal;
+      u_goal.real = this->goal;
+      *(outbuffer + offset + 0) = (u_goal.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_goal.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_goal.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_goal.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->goal);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_goal;
+      u_goal.base = 0;
+      u_goal.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_goal.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_goal.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_goal.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->goal = u_goal.real;
+      offset += sizeof(this->goal);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestGoal"; };
+    const char * getMD5(){ return "18df0149936b7aa95588e3862476ebde"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestRequestAction_h
+#define _ROS_actionlib_TestRequestAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib/TestRequestActionGoal.h"
+#include "actionlib/TestRequestActionResult.h"
+#include "actionlib/TestRequestActionFeedback.h"
+
+namespace actionlib
+{
+
+  class TestRequestAction : public ros::Msg
+  {
+    public:
+      actionlib::TestRequestActionGoal action_goal;
+      actionlib::TestRequestActionResult action_result;
+      actionlib::TestRequestActionFeedback action_feedback;
+
+    TestRequestAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestAction"; };
+    const char * getMD5(){ return "dc44b1f4045dbf0d1db54423b3b86b30"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestRequestActionFeedback_h
+#define _ROS_actionlib_TestRequestActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TestRequestFeedback.h"
+
+namespace actionlib
+{
+
+  class TestRequestActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TestRequestFeedback feedback;
+
+    TestRequestActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestRequestActionGoal_h
+#define _ROS_actionlib_TestRequestActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib/TestRequestGoal.h"
+
+namespace actionlib
+{
+
+  class TestRequestActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      actionlib::TestRequestGoal goal;
+
+    TestRequestActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestActionGoal"; };
+    const char * getMD5(){ return "1889556d3fef88f821c7cb004e4251f3"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TestRequestActionResult_h
+#define _ROS_actionlib_TestRequestActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TestRequestResult.h"
+
+namespace actionlib
+{
+
+  class TestRequestActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TestRequestResult result;
+
+    TestRequestActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestActionResult"; };
+    const char * getMD5(){ return "0476d1fdf437a3a6e7d6d0e9f5561298"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_actionlib_TestRequestFeedback_h
+#define _ROS_actionlib_TestRequestFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TestRequestFeedback : public ros::Msg
+  {
+    public:
+
+    TestRequestFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,207 @@
+#ifndef _ROS_actionlib_TestRequestGoal_h
+#define _ROS_actionlib_TestRequestGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+
+namespace actionlib
+{
+
+  class TestRequestGoal : public ros::Msg
+  {
+    public:
+      int32_t terminate_status;
+      bool ignore_cancel;
+      const char* result_text;
+      int32_t the_result;
+      bool is_simple_client;
+      ros::Duration delay_accept;
+      ros::Duration delay_terminate;
+      ros::Duration pause_status;
+      enum { TERMINATE_SUCCESS =  0 };
+      enum { TERMINATE_ABORTED =  1 };
+      enum { TERMINATE_REJECTED =  2 };
+      enum { TERMINATE_LOSE =  3 };
+      enum { TERMINATE_DROP =  4 };
+      enum { TERMINATE_EXCEPTION =  5 };
+
+    TestRequestGoal():
+      terminate_status(0),
+      ignore_cancel(0),
+      result_text(""),
+      the_result(0),
+      is_simple_client(0),
+      delay_accept(),
+      delay_terminate(),
+      pause_status()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_terminate_status;
+      u_terminate_status.real = this->terminate_status;
+      *(outbuffer + offset + 0) = (u_terminate_status.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_terminate_status.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_terminate_status.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_terminate_status.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->terminate_status);
+      union {
+        bool real;
+        uint8_t base;
+      } u_ignore_cancel;
+      u_ignore_cancel.real = this->ignore_cancel;
+      *(outbuffer + offset + 0) = (u_ignore_cancel.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->ignore_cancel);
+      uint32_t length_result_text = strlen(this->result_text);
+      memcpy(outbuffer + offset, &length_result_text, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->result_text, length_result_text);
+      offset += length_result_text;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_the_result;
+      u_the_result.real = this->the_result;
+      *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->the_result);
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_simple_client;
+      u_is_simple_client.real = this->is_simple_client;
+      *(outbuffer + offset + 0) = (u_is_simple_client.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_simple_client);
+      *(outbuffer + offset + 0) = (this->delay_accept.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->delay_accept.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->delay_accept.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->delay_accept.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delay_accept.sec);
+      *(outbuffer + offset + 0) = (this->delay_accept.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->delay_accept.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->delay_accept.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->delay_accept.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delay_accept.nsec);
+      *(outbuffer + offset + 0) = (this->delay_terminate.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->delay_terminate.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->delay_terminate.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->delay_terminate.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delay_terminate.sec);
+      *(outbuffer + offset + 0) = (this->delay_terminate.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->delay_terminate.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->delay_terminate.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->delay_terminate.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delay_terminate.nsec);
+      *(outbuffer + offset + 0) = (this->pause_status.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pause_status.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pause_status.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pause_status.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pause_status.sec);
+      *(outbuffer + offset + 0) = (this->pause_status.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pause_status.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pause_status.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pause_status.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pause_status.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_terminate_status;
+      u_terminate_status.base = 0;
+      u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->terminate_status = u_terminate_status.real;
+      offset += sizeof(this->terminate_status);
+      union {
+        bool real;
+        uint8_t base;
+      } u_ignore_cancel;
+      u_ignore_cancel.base = 0;
+      u_ignore_cancel.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->ignore_cancel = u_ignore_cancel.real;
+      offset += sizeof(this->ignore_cancel);
+      uint32_t length_result_text;
+      memcpy(&length_result_text, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_result_text; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_result_text-1]=0;
+      this->result_text = (char *)(inbuffer + offset-1);
+      offset += length_result_text;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_the_result;
+      u_the_result.base = 0;
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->the_result = u_the_result.real;
+      offset += sizeof(this->the_result);
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_simple_client;
+      u_is_simple_client.base = 0;
+      u_is_simple_client.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_simple_client = u_is_simple_client.real;
+      offset += sizeof(this->is_simple_client);
+      this->delay_accept.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->delay_accept.sec);
+      this->delay_accept.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->delay_accept.nsec);
+      this->delay_terminate.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->delay_terminate.sec);
+      this->delay_terminate.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->delay_terminate.nsec);
+      this->pause_status.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->pause_status.sec);
+      this->pause_status.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->pause_status.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestGoal"; };
+    const char * getMD5(){ return "db5d00ba98302d6c6dd3737e9a03ceea"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestRequestResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_actionlib_TestRequestResult_h
+#define _ROS_actionlib_TestRequestResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TestRequestResult : public ros::Msg
+  {
+    public:
+      int32_t the_result;
+      bool is_simple_server;
+
+    TestRequestResult():
+      the_result(0),
+      is_simple_server(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_the_result;
+      u_the_result.real = this->the_result;
+      *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->the_result);
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_simple_server;
+      u_is_simple_server.real = this->is_simple_server;
+      *(outbuffer + offset + 0) = (u_is_simple_server.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_simple_server);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_the_result;
+      u_the_result.base = 0;
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->the_result = u_the_result.real;
+      offset += sizeof(this->the_result);
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_simple_server;
+      u_is_simple_server.base = 0;
+      u_is_simple_server.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_simple_server = u_is_simple_server.real;
+      offset += sizeof(this->is_simple_server);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestRequestResult"; };
+    const char * getMD5(){ return "61c2364524499c7c5017e2f3fce7ba06"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TestResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_actionlib_TestResult_h
+#define _ROS_actionlib_TestResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TestResult : public ros::Msg
+  {
+    public:
+      int32_t result;
+
+    TestResult():
+      result(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_result;
+      u_result.real = this->result;
+      *(outbuffer + offset + 0) = (u_result.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_result.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_result.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_result.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->result);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_result;
+      u_result.base = 0;
+      u_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->result = u_result.real;
+      offset += sizeof(this->result);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TestResult"; };
+    const char * getMD5(){ return "034a8e20d6a306665e3a5b340fab3f09"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TwoIntsAction_h
+#define _ROS_actionlib_TwoIntsAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib/TwoIntsActionGoal.h"
+#include "actionlib/TwoIntsActionResult.h"
+#include "actionlib/TwoIntsActionFeedback.h"
+
+namespace actionlib
+{
+
+  class TwoIntsAction : public ros::Msg
+  {
+    public:
+      actionlib::TwoIntsActionGoal action_goal;
+      actionlib::TwoIntsActionResult action_result;
+      actionlib::TwoIntsActionFeedback action_feedback;
+
+    TwoIntsAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsAction"; };
+    const char * getMD5(){ return "6d1aa538c4bd6183a2dfb7fcac41ee50"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TwoIntsActionFeedback_h
+#define _ROS_actionlib_TwoIntsActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TwoIntsFeedback.h"
+
+namespace actionlib
+{
+
+  class TwoIntsActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TwoIntsFeedback feedback;
+
+    TwoIntsActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TwoIntsActionGoal_h
+#define _ROS_actionlib_TwoIntsActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib/TwoIntsGoal.h"
+
+namespace actionlib
+{
+
+  class TwoIntsActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      actionlib::TwoIntsGoal goal;
+
+    TwoIntsActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsActionGoal"; };
+    const char * getMD5(){ return "684a2db55d6ffb8046fb9d6764ce0860"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_TwoIntsActionResult_h
+#define _ROS_actionlib_TwoIntsActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib/TwoIntsResult.h"
+
+namespace actionlib
+{
+
+  class TwoIntsActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib::TwoIntsResult result;
+
+    TwoIntsActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsActionResult"; };
+    const char * getMD5(){ return "3ba7dea8b8cddcae4528ade4ef74b6e7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_actionlib_TwoIntsFeedback_h
+#define _ROS_actionlib_TwoIntsFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TwoIntsFeedback : public ros::Msg
+  {
+    public:
+
+    TwoIntsFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_actionlib_TwoIntsGoal_h
+#define _ROS_actionlib_TwoIntsGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TwoIntsGoal : public ros::Msg
+  {
+    public:
+      int64_t a;
+      int64_t b;
+
+    TwoIntsGoal():
+      a(0),
+      b(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->b);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsGoal"; };
+    const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib/TwoIntsResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_actionlib_TwoIntsResult_h
+#define _ROS_actionlib_TwoIntsResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+  class TwoIntsResult : public ros::Msg
+  {
+    public:
+      int64_t sum;
+
+    TwoIntsResult():
+      sum(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.real = this->sum;
+      *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sum);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.base = 0;
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sum = u_sum.real;
+      offset += sizeof(this->sum);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib/TwoIntsResult"; };
+    const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_msgs/GoalID.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalID.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_actionlib_msgs_GoalID_h
+#define _ROS_actionlib_msgs_GoalID_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace actionlib_msgs
+{
+
+  class GoalID : public ros::Msg
+  {
+    public:
+      ros::Time stamp;
+      const char* id;
+
+    GoalID():
+      stamp(),
+      id("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.sec);
+      *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_id = strlen(this->id);
+      memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->id, length_id);
+      offset += length_id;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->stamp.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.sec);
+      this->stamp.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_id;
+      memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_id-1]=0;
+      this->id = (char *)(inbuffer + offset-1);
+      offset += length_id;
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_msgs/GoalID"; };
+    const char * getMD5(){ return "302881f31927c1df708a2dbab0e80ee8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_msgs/GoalStatus.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalStatus.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,75 @@
+#ifndef _ROS_actionlib_msgs_GoalStatus_h
+#define _ROS_actionlib_msgs_GoalStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib_msgs/GoalID.h"
+
+namespace actionlib_msgs
+{
+
+  class GoalStatus : public ros::Msg
+  {
+    public:
+      actionlib_msgs::GoalID goal_id;
+      uint8_t status;
+      const char* text;
+      enum { PENDING =  0    };
+      enum { ACTIVE =  1    };
+      enum { PREEMPTED =  2    };
+      enum { SUCCEEDED =  3    };
+      enum { ABORTED =  4    };
+      enum { REJECTED =  5    };
+      enum { PREEMPTING =  6    };
+      enum { RECALLING =  7    };
+      enum { RECALLED =  8    };
+      enum { LOST =  9    };
+
+    GoalStatus():
+      goal_id(),
+      status(0),
+      text("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->goal_id.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->status >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->status);
+      uint32_t length_text = strlen(this->text);
+      memcpy(outbuffer + offset, &length_text, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->text, length_text);
+      offset += length_text;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      this->status =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->status);
+      uint32_t length_text;
+      memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_text; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_text-1]=0;
+      this->text = (char *)(inbuffer + offset-1);
+      offset += length_text;
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_msgs/GoalStatus"; };
+    const char * getMD5(){ return "d388f9b87b3c471f784434d671988d4a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_msgs/GoalStatusArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalStatusArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_actionlib_msgs_GoalStatusArray_h
+#define _ROS_actionlib_msgs_GoalStatusArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+
+namespace actionlib_msgs
+{
+
+  class GoalStatusArray : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t status_list_length;
+      actionlib_msgs::GoalStatus st_status_list;
+      actionlib_msgs::GoalStatus * status_list;
+
+    GoalStatusArray():
+      header(),
+      status_list_length(0), status_list(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = status_list_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < status_list_length; i++){
+      offset += this->status_list[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t status_list_lengthT = *(inbuffer + offset++);
+      if(status_list_lengthT > status_list_length)
+        this->status_list = (actionlib_msgs::GoalStatus*)realloc(this->status_list, status_list_lengthT * sizeof(actionlib_msgs::GoalStatus));
+      offset += 3;
+      status_list_length = status_list_lengthT;
+      for( uint8_t i = 0; i < status_list_length; i++){
+      offset += this->st_status_list.deserialize(inbuffer + offset);
+        memcpy( &(this->status_list[i]), &(this->st_status_list), sizeof(actionlib_msgs::GoalStatus));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_msgs/GoalStatusArray"; };
+    const char * getMD5(){ return "8b2b82f13216d0a8ea88bd3af735e619"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_AveragingAction_h
+#define _ROS_actionlib_tutorials_AveragingAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib_tutorials/AveragingActionGoal.h"
+#include "actionlib_tutorials/AveragingActionResult.h"
+#include "actionlib_tutorials/AveragingActionFeedback.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingAction : public ros::Msg
+  {
+    public:
+      actionlib_tutorials::AveragingActionGoal action_goal;
+      actionlib_tutorials::AveragingActionResult action_result;
+      actionlib_tutorials::AveragingActionFeedback action_feedback;
+
+    AveragingAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingAction"; };
+    const char * getMD5(){ return "628678f2b4fa6a5951746a4a2d39e716"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionFeedback_h
+#define _ROS_actionlib_tutorials_AveragingActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib_tutorials/AveragingFeedback.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib_tutorials::AveragingFeedback feedback;
+
+    AveragingActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingActionFeedback"; };
+    const char * getMD5(){ return "78a4a09241b1791069223ae7ebd5b16b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionGoal_h
+#define _ROS_actionlib_tutorials_AveragingActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib_tutorials/AveragingGoal.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      actionlib_tutorials::AveragingGoal goal;
+
+    AveragingActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingActionGoal"; };
+    const char * getMD5(){ return "1561825b734ebd6039851c501e3fb570"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionResult_h
+#define _ROS_actionlib_tutorials_AveragingActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib_tutorials/AveragingResult.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib_tutorials::AveragingResult result;
+
+    AveragingActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingActionResult"; };
+    const char * getMD5(){ return "8672cb489d347580acdcd05c5d497497"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,130 @@
+#ifndef _ROS_actionlib_tutorials_AveragingFeedback_h
+#define _ROS_actionlib_tutorials_AveragingFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingFeedback : public ros::Msg
+  {
+    public:
+      int32_t sample;
+      float data;
+      float mean;
+      float std_dev;
+
+    AveragingFeedback():
+      sample(0),
+      data(0),
+      mean(0),
+      std_dev(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sample;
+      u_sample.real = this->sample;
+      *(outbuffer + offset + 0) = (u_sample.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sample.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sample.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sample.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sample);
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      union {
+        float real;
+        uint32_t base;
+      } u_mean;
+      u_mean.real = this->mean;
+      *(outbuffer + offset + 0) = (u_mean.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mean.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mean.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mean.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->mean);
+      union {
+        float real;
+        uint32_t base;
+      } u_std_dev;
+      u_std_dev.real = this->std_dev;
+      *(outbuffer + offset + 0) = (u_std_dev.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_std_dev.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_std_dev.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_std_dev.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->std_dev);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sample;
+      u_sample.base = 0;
+      u_sample.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sample.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sample.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sample.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->sample = u_sample.real;
+      offset += sizeof(this->sample);
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+      union {
+        float real;
+        uint32_t base;
+      } u_mean;
+      u_mean.base = 0;
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->mean = u_mean.real;
+      offset += sizeof(this->mean);
+      union {
+        float real;
+        uint32_t base;
+      } u_std_dev;
+      u_std_dev.base = 0;
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->std_dev = u_std_dev.real;
+      offset += sizeof(this->std_dev);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingFeedback"; };
+    const char * getMD5(){ return "9e8dfc53c2f2a032ca33fa80ec46fd4f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_actionlib_tutorials_AveragingGoal_h
+#define _ROS_actionlib_tutorials_AveragingGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingGoal : public ros::Msg
+  {
+    public:
+      int32_t samples;
+
+    AveragingGoal():
+      samples(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_samples;
+      u_samples.real = this->samples;
+      *(outbuffer + offset + 0) = (u_samples.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_samples.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_samples.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_samples.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->samples);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_samples;
+      u_samples.base = 0;
+      u_samples.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_samples.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_samples.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_samples.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->samples = u_samples.real;
+      offset += sizeof(this->samples);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingGoal"; };
+    const char * getMD5(){ return "32c9b10ef9b253faa93b93f564762c8f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/AveragingResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,84 @@
+#ifndef _ROS_actionlib_tutorials_AveragingResult_h
+#define _ROS_actionlib_tutorials_AveragingResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class AveragingResult : public ros::Msg
+  {
+    public:
+      float mean;
+      float std_dev;
+
+    AveragingResult():
+      mean(0),
+      std_dev(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_mean;
+      u_mean.real = this->mean;
+      *(outbuffer + offset + 0) = (u_mean.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mean.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mean.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mean.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->mean);
+      union {
+        float real;
+        uint32_t base;
+      } u_std_dev;
+      u_std_dev.real = this->std_dev;
+      *(outbuffer + offset + 0) = (u_std_dev.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_std_dev.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_std_dev.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_std_dev.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->std_dev);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_mean;
+      u_mean.base = 0;
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mean.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->mean = u_mean.real;
+      offset += sizeof(this->mean);
+      union {
+        float real;
+        uint32_t base;
+      } u_std_dev;
+      u_std_dev.base = 0;
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->std_dev = u_std_dev.real;
+      offset += sizeof(this->std_dev);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/AveragingResult"; };
+    const char * getMD5(){ return "d5c7decf6df75ffb4367a05c1bcc7612"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciAction_h
+#define _ROS_actionlib_tutorials_FibonacciAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "actionlib_tutorials/FibonacciActionGoal.h"
+#include "actionlib_tutorials/FibonacciActionResult.h"
+#include "actionlib_tutorials/FibonacciActionFeedback.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciAction : public ros::Msg
+  {
+    public:
+      actionlib_tutorials::FibonacciActionGoal action_goal;
+      actionlib_tutorials::FibonacciActionResult action_result;
+      actionlib_tutorials::FibonacciActionFeedback action_feedback;
+
+    FibonacciAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciAction"; };
+    const char * getMD5(){ return "f59df5767bf7634684781c92598b2406"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionFeedback_h
+#define _ROS_actionlib_tutorials_FibonacciActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib_tutorials/FibonacciFeedback.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib_tutorials::FibonacciFeedback feedback;
+
+    FibonacciActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciActionFeedback"; };
+    const char * getMD5(){ return "73b8497a9f629a31c0020900e4148f07"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionGoal_h
+#define _ROS_actionlib_tutorials_FibonacciActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "actionlib_tutorials/FibonacciGoal.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      actionlib_tutorials::FibonacciGoal goal;
+
+    FibonacciActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciActionGoal"; };
+    const char * getMD5(){ return "006871c7fa1d0e3d5fe2226bf17b2a94"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionResult_h
+#define _ROS_actionlib_tutorials_FibonacciActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "actionlib_tutorials/FibonacciResult.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      actionlib_tutorials::FibonacciResult result;
+
+    FibonacciActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciActionResult"; };
+    const char * getMD5(){ return "bee73a9fe29ae25e966e105f5553dd03"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciFeedback_h
+#define _ROS_actionlib_tutorials_FibonacciFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciFeedback : public ros::Msg
+  {
+    public:
+      uint8_t sequence_length;
+      int32_t st_sequence;
+      int32_t * sequence;
+
+    FibonacciFeedback():
+      sequence_length(0), sequence(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = sequence_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < sequence_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sequencei;
+      u_sequencei.real = this->sequence[i];
+      *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sequence[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t sequence_lengthT = *(inbuffer + offset++);
+      if(sequence_lengthT > sequence_length)
+        this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t));
+      offset += 3;
+      sequence_length = sequence_lengthT;
+      for( uint8_t i = 0; i < sequence_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_sequence;
+      u_st_sequence.base = 0;
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_sequence = u_st_sequence.real;
+      offset += sizeof(this->st_sequence);
+        memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciFeedback"; };
+    const char * getMD5(){ return "b81e37d2a31925a0e8ae261a8699cb79"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciGoal_h
+#define _ROS_actionlib_tutorials_FibonacciGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciGoal : public ros::Msg
+  {
+    public:
+      int32_t order;
+
+    FibonacciGoal():
+      order(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_order;
+      u_order.real = this->order;
+      *(outbuffer + offset + 0) = (u_order.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_order.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_order.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_order.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->order);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_order;
+      u_order.base = 0;
+      u_order.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_order.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_order.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_order.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->order = u_order.real;
+      offset += sizeof(this->order);
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciGoal"; };
+    const char * getMD5(){ return "6889063349a00b249bd1661df429d822"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 actionlib_tutorials/FibonacciResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciResult_h
+#define _ROS_actionlib_tutorials_FibonacciResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace actionlib_tutorials
+{
+
+  class FibonacciResult : public ros::Msg
+  {
+    public:
+      uint8_t sequence_length;
+      int32_t st_sequence;
+      int32_t * sequence;
+
+    FibonacciResult():
+      sequence_length(0), sequence(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = sequence_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < sequence_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sequencei;
+      u_sequencei.real = this->sequence[i];
+      *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sequence[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t sequence_lengthT = *(inbuffer + offset++);
+      if(sequence_lengthT > sequence_length)
+        this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t));
+      offset += 3;
+      sequence_length = sequence_lengthT;
+      for( uint8_t i = 0; i < sequence_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_sequence;
+      u_st_sequence.base = 0;
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_sequence = u_st_sequence.real;
+      offset += sizeof(this->st_sequence);
+        memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "actionlib_tutorials/FibonacciResult"; };
+    const char * getMD5(){ return "b81e37d2a31925a0e8ae261a8699cb79"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 bond/Constants.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bond/Constants.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,44 @@
+#ifndef _ROS_bond_Constants_h
+#define _ROS_bond_Constants_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace bond
+{
+
+  class Constants : public ros::Msg
+  {
+    public:
+      enum { DEAD_PUBLISH_PERIOD =  0.05 };
+      enum { DEFAULT_CONNECT_TIMEOUT =  10.0 };
+      enum { DEFAULT_HEARTBEAT_TIMEOUT =  4.0 };
+      enum { DEFAULT_DISCONNECT_TIMEOUT =  2.0 };
+      enum { DEFAULT_HEARTBEAT_PERIOD =  1.0 };
+      enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout };
+
+    Constants()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "bond/Constants"; };
+    const char * getMD5(){ return "6fc594dc1d7bd7919077042712f8c8b0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 bond/Status.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bond/Status.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,138 @@
+#ifndef _ROS_bond_Status_h
+#define _ROS_bond_Status_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace bond
+{
+
+  class Status : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* id;
+      const char* instance_id;
+      bool active;
+      float heartbeat_timeout;
+      float heartbeat_period;
+
+    Status():
+      header(),
+      id(""),
+      instance_id(""),
+      active(0),
+      heartbeat_timeout(0),
+      heartbeat_period(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_id = strlen(this->id);
+      memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->id, length_id);
+      offset += length_id;
+      uint32_t length_instance_id = strlen(this->instance_id);
+      memcpy(outbuffer + offset, &length_instance_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->instance_id, length_instance_id);
+      offset += length_instance_id;
+      union {
+        bool real;
+        uint8_t base;
+      } u_active;
+      u_active.real = this->active;
+      *(outbuffer + offset + 0) = (u_active.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->active);
+      union {
+        float real;
+        uint32_t base;
+      } u_heartbeat_timeout;
+      u_heartbeat_timeout.real = this->heartbeat_timeout;
+      *(outbuffer + offset + 0) = (u_heartbeat_timeout.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_heartbeat_timeout.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_heartbeat_timeout.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_heartbeat_timeout.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->heartbeat_timeout);
+      union {
+        float real;
+        uint32_t base;
+      } u_heartbeat_period;
+      u_heartbeat_period.real = this->heartbeat_period;
+      *(outbuffer + offset + 0) = (u_heartbeat_period.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_heartbeat_period.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_heartbeat_period.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_heartbeat_period.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->heartbeat_period);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_id;
+      memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_id-1]=0;
+      this->id = (char *)(inbuffer + offset-1);
+      offset += length_id;
+      uint32_t length_instance_id;
+      memcpy(&length_instance_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_instance_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_instance_id-1]=0;
+      this->instance_id = (char *)(inbuffer + offset-1);
+      offset += length_instance_id;
+      union {
+        bool real;
+        uint8_t base;
+      } u_active;
+      u_active.base = 0;
+      u_active.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->active = u_active.real;
+      offset += sizeof(this->active);
+      union {
+        float real;
+        uint32_t base;
+      } u_heartbeat_timeout;
+      u_heartbeat_timeout.base = 0;
+      u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->heartbeat_timeout = u_heartbeat_timeout.real;
+      offset += sizeof(this->heartbeat_timeout);
+      union {
+        float real;
+        uint32_t base;
+      } u_heartbeat_period;
+      u_heartbeat_period.base = 0;
+      u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->heartbeat_period = u_heartbeat_period.real;
+      offset += sizeof(this->heartbeat_period);
+     return offset;
+    }
+
+    const char * getType(){ return "bond/Status"; };
+    const char * getMD5(){ return "eacc84bf5d65b6777d4c50f463dfb9c8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryAction_h
+#define _ROS_control_msgs_FollowJointTrajectoryAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/FollowJointTrajectoryActionGoal.h"
+#include "control_msgs/FollowJointTrajectoryActionResult.h"
+#include "control_msgs/FollowJointTrajectoryActionFeedback.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryAction : public ros::Msg
+  {
+    public:
+      control_msgs::FollowJointTrajectoryActionGoal action_goal;
+      control_msgs::FollowJointTrajectoryActionResult action_result;
+      control_msgs::FollowJointTrajectoryActionFeedback action_feedback;
+
+    FollowJointTrajectoryAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryAction"; };
+    const char * getMD5(){ return "bc4f9b743838566551c0390c65f1a248"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/FollowJointTrajectoryFeedback.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::FollowJointTrajectoryFeedback feedback;
+
+    FollowJointTrajectoryActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryActionFeedback"; };
+    const char * getMD5(){ return "d8920dc4eae9fc107e00999cce4be641"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionGoal_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "control_msgs/FollowJointTrajectoryGoal.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      control_msgs::FollowJointTrajectoryGoal goal;
+
+    FollowJointTrajectoryActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryActionGoal"; };
+    const char * getMD5(){ return "cff5c1d533bf2f82dd0138d57f4304bb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionResult_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/FollowJointTrajectoryResult.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::FollowJointTrajectoryResult result;
+
+    FollowJointTrajectoryActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryActionResult"; };
+    const char * getMD5(){ return "c4fb3b000dc9da4fd99699380efcc5d9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,88 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryFeedback_h
+#define _ROS_control_msgs_FollowJointTrajectoryFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "trajectory_msgs/JointTrajectoryPoint.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      trajectory_msgs::JointTrajectoryPoint desired;
+      trajectory_msgs::JointTrajectoryPoint actual;
+      trajectory_msgs::JointTrajectoryPoint error;
+
+    FollowJointTrajectoryFeedback():
+      header(),
+      joint_names_length(0), joint_names(NULL),
+      desired(),
+      actual(),
+      error()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      offset += this->desired.serialize(outbuffer + offset);
+      offset += this->actual.serialize(outbuffer + offset);
+      offset += this->error.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      offset += this->desired.deserialize(inbuffer + offset);
+      offset += this->actual.deserialize(inbuffer + offset);
+      offset += this->error.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryFeedback"; };
+    const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,107 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryGoal_h
+#define _ROS_control_msgs_FollowJointTrajectoryGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "trajectory_msgs/JointTrajectory.h"
+#include "control_msgs/JointTolerance.h"
+#include "ros/duration.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryGoal : public ros::Msg
+  {
+    public:
+      trajectory_msgs::JointTrajectory trajectory;
+      uint8_t path_tolerance_length;
+      control_msgs::JointTolerance st_path_tolerance;
+      control_msgs::JointTolerance * path_tolerance;
+      uint8_t goal_tolerance_length;
+      control_msgs::JointTolerance st_goal_tolerance;
+      control_msgs::JointTolerance * goal_tolerance;
+      ros::Duration goal_time_tolerance;
+
+    FollowJointTrajectoryGoal():
+      trajectory(),
+      path_tolerance_length(0), path_tolerance(NULL),
+      goal_tolerance_length(0), goal_tolerance(NULL),
+      goal_time_tolerance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->trajectory.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = path_tolerance_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < path_tolerance_length; i++){
+      offset += this->path_tolerance[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = goal_tolerance_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < goal_tolerance_length; i++){
+      offset += this->goal_tolerance[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->goal_time_tolerance.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->goal_time_tolerance.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->goal_time_tolerance.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->goal_time_tolerance.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->goal_time_tolerance.sec);
+      *(outbuffer + offset + 0) = (this->goal_time_tolerance.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->goal_time_tolerance.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->goal_time_tolerance.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->goal_time_tolerance.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->goal_time_tolerance.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->trajectory.deserialize(inbuffer + offset);
+      uint8_t path_tolerance_lengthT = *(inbuffer + offset++);
+      if(path_tolerance_lengthT > path_tolerance_length)
+        this->path_tolerance = (control_msgs::JointTolerance*)realloc(this->path_tolerance, path_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
+      offset += 3;
+      path_tolerance_length = path_tolerance_lengthT;
+      for( uint8_t i = 0; i < path_tolerance_length; i++){
+      offset += this->st_path_tolerance.deserialize(inbuffer + offset);
+        memcpy( &(this->path_tolerance[i]), &(this->st_path_tolerance), sizeof(control_msgs::JointTolerance));
+      }
+      uint8_t goal_tolerance_lengthT = *(inbuffer + offset++);
+      if(goal_tolerance_lengthT > goal_tolerance_length)
+        this->goal_tolerance = (control_msgs::JointTolerance*)realloc(this->goal_tolerance, goal_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
+      offset += 3;
+      goal_tolerance_length = goal_tolerance_lengthT;
+      for( uint8_t i = 0; i < goal_tolerance_length; i++){
+      offset += this->st_goal_tolerance.deserialize(inbuffer + offset);
+        memcpy( &(this->goal_tolerance[i]), &(this->st_goal_tolerance), sizeof(control_msgs::JointTolerance));
+      }
+      this->goal_time_tolerance.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->goal_time_tolerance.sec);
+      this->goal_time_tolerance.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->goal_time_tolerance.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryGoal"; };
+    const char * getMD5(){ return "69636787b6ecbde4d61d711979bc7ecb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/FollowJointTrajectoryResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,83 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryResult_h
+#define _ROS_control_msgs_FollowJointTrajectoryResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class FollowJointTrajectoryResult : public ros::Msg
+  {
+    public:
+      int32_t error_code;
+      const char* error_string;
+      enum { SUCCESSFUL =  0 };
+      enum { INVALID_GOAL =  -1 };
+      enum { INVALID_JOINTS =  -2 };
+      enum { OLD_HEADER_TIMESTAMP =  -3 };
+      enum { PATH_TOLERANCE_VIOLATED =  -4 };
+      enum { GOAL_TOLERANCE_VIOLATED =  -5 };
+
+    FollowJointTrajectoryResult():
+      error_code(0),
+      error_string("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_error_code;
+      u_error_code.real = this->error_code;
+      *(outbuffer + offset + 0) = (u_error_code.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_error_code.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_error_code.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_error_code.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->error_code);
+      uint32_t length_error_string = strlen(this->error_string);
+      memcpy(outbuffer + offset, &length_error_string, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->error_string, length_error_string);
+      offset += length_error_string;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_error_code;
+      u_error_code.base = 0;
+      u_error_code.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_error_code.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_error_code.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_error_code.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->error_code = u_error_code.real;
+      offset += sizeof(this->error_code);
+      uint32_t length_error_string;
+      memcpy(&length_error_string, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_error_string; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_error_string-1]=0;
+      this->error_string = (char *)(inbuffer + offset-1);
+      offset += length_error_string;
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/FollowJointTrajectoryResult"; };
+    const char * getMD5(){ return "493383b18409bfb604b4e26c676401d2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommand.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommand.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_control_msgs_GripperCommand_h
+#define _ROS_control_msgs_GripperCommand_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class GripperCommand : public ros::Msg
+  {
+    public:
+      double position;
+      double max_effort;
+
+    GripperCommand():
+      position(0),
+      max_effort(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_effort;
+      u_max_effort.real = this->max_effort;
+      *(outbuffer + offset + 0) = (u_max_effort.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_effort.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_effort.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_effort.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_effort.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_effort.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_effort.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_effort.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_effort);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_effort;
+      u_max_effort.base = 0;
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_effort = u_max_effort.real;
+      offset += sizeof(this->max_effort);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommand"; };
+    const char * getMD5(){ return "680acaff79486f017132a7f198d40f08"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_GripperCommandAction_h
+#define _ROS_control_msgs_GripperCommandAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/GripperCommandActionGoal.h"
+#include "control_msgs/GripperCommandActionResult.h"
+#include "control_msgs/GripperCommandActionFeedback.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandAction : public ros::Msg
+  {
+    public:
+      control_msgs::GripperCommandActionGoal action_goal;
+      control_msgs::GripperCommandActionResult action_result;
+      control_msgs::GripperCommandActionFeedback action_feedback;
+
+    GripperCommandAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandAction"; };
+    const char * getMD5(){ return "950b2a6ebe831f5d4f4ceaba3d8be01e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_GripperCommandActionFeedback_h
+#define _ROS_control_msgs_GripperCommandActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/GripperCommandFeedback.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::GripperCommandFeedback feedback;
+
+    GripperCommandActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandActionFeedback"; };
+    const char * getMD5(){ return "653dff30c045f5e6ff3feb3409f4558d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_GripperCommandActionGoal_h
+#define _ROS_control_msgs_GripperCommandActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "control_msgs/GripperCommandGoal.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      control_msgs::GripperCommandGoal goal;
+
+    GripperCommandActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandActionGoal"; };
+    const char * getMD5(){ return "aa581f648a35ed681db2ec0bf7a82bea"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_GripperCommandActionResult_h
+#define _ROS_control_msgs_GripperCommandActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/GripperCommandResult.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::GripperCommandResult result;
+
+    GripperCommandActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandActionResult"; };
+    const char * getMD5(){ return "143702cb2df0f163c5283cedc5efc6b6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,134 @@
+#ifndef _ROS_control_msgs_GripperCommandFeedback_h
+#define _ROS_control_msgs_GripperCommandFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandFeedback : public ros::Msg
+  {
+    public:
+      double position;
+      double effort;
+      bool stalled;
+      bool reached_goal;
+
+    GripperCommandFeedback():
+      position(0),
+      effort(0),
+      stalled(0),
+      reached_goal(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.real = this->effort;
+      *(outbuffer + offset + 0) = (u_effort.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_effort.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_effort.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_effort.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_effort.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_effort.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_effort.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_effort.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->effort);
+      union {
+        bool real;
+        uint8_t base;
+      } u_stalled;
+      u_stalled.real = this->stalled;
+      *(outbuffer + offset + 0) = (u_stalled.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->stalled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_reached_goal;
+      u_reached_goal.real = this->reached_goal;
+      *(outbuffer + offset + 0) = (u_reached_goal.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->reached_goal);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.base = 0;
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->effort = u_effort.real;
+      offset += sizeof(this->effort);
+      union {
+        bool real;
+        uint8_t base;
+      } u_stalled;
+      u_stalled.base = 0;
+      u_stalled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->stalled = u_stalled.real;
+      offset += sizeof(this->stalled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_reached_goal;
+      u_reached_goal.base = 0;
+      u_reached_goal.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->reached_goal = u_reached_goal.real;
+      offset += sizeof(this->reached_goal);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandFeedback"; };
+    const char * getMD5(){ return "e4cbff56d3562bcf113da5a5adeef91f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,43 @@
+#ifndef _ROS_control_msgs_GripperCommandGoal_h
+#define _ROS_control_msgs_GripperCommandGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/GripperCommand.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandGoal : public ros::Msg
+  {
+    public:
+      control_msgs::GripperCommand command;
+
+    GripperCommandGoal():
+      command()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->command.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->command.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandGoal"; };
+    const char * getMD5(){ return "86fd82f4ddc48a4cb6856cfa69217e43"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/GripperCommandResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,134 @@
+#ifndef _ROS_control_msgs_GripperCommandResult_h
+#define _ROS_control_msgs_GripperCommandResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class GripperCommandResult : public ros::Msg
+  {
+    public:
+      double position;
+      double effort;
+      bool stalled;
+      bool reached_goal;
+
+    GripperCommandResult():
+      position(0),
+      effort(0),
+      stalled(0),
+      reached_goal(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.real = this->effort;
+      *(outbuffer + offset + 0) = (u_effort.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_effort.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_effort.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_effort.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_effort.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_effort.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_effort.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_effort.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->effort);
+      union {
+        bool real;
+        uint8_t base;
+      } u_stalled;
+      u_stalled.real = this->stalled;
+      *(outbuffer + offset + 0) = (u_stalled.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->stalled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_reached_goal;
+      u_reached_goal.real = this->reached_goal;
+      *(outbuffer + offset + 0) = (u_reached_goal.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->reached_goal);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.base = 0;
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->effort = u_effort.real;
+      offset += sizeof(this->effort);
+      union {
+        bool real;
+        uint8_t base;
+      } u_stalled;
+      u_stalled.base = 0;
+      u_stalled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->stalled = u_stalled.real;
+      offset += sizeof(this->stalled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_reached_goal;
+      u_reached_goal.base = 0;
+      u_reached_goal.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->reached_goal = u_reached_goal.real;
+      offset += sizeof(this->reached_goal);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/GripperCommandResult"; };
+    const char * getMD5(){ return "e4cbff56d3562bcf113da5a5adeef91f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointControllerState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointControllerState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,353 @@
+#ifndef _ROS_control_msgs_JointControllerState_h
+#define _ROS_control_msgs_JointControllerState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace control_msgs
+{
+
+  class JointControllerState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double set_point;
+      double process_value;
+      double process_value_dot;
+      double error;
+      double time_step;
+      double command;
+      double p;
+      double i;
+      double d;
+      double i_clamp;
+
+    JointControllerState():
+      header(),
+      set_point(0),
+      process_value(0),
+      process_value_dot(0),
+      error(0),
+      time_step(0),
+      command(0),
+      p(0),
+      i(0),
+      d(0),
+      i_clamp(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_set_point;
+      u_set_point.real = this->set_point;
+      *(outbuffer + offset + 0) = (u_set_point.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_set_point.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_set_point.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_set_point.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_set_point.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_set_point.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_set_point.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_set_point.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->set_point);
+      union {
+        double real;
+        uint64_t base;
+      } u_process_value;
+      u_process_value.real = this->process_value;
+      *(outbuffer + offset + 0) = (u_process_value.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_process_value.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_process_value.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_process_value.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_process_value.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_process_value.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_process_value.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_process_value.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->process_value);
+      union {
+        double real;
+        uint64_t base;
+      } u_process_value_dot;
+      u_process_value_dot.real = this->process_value_dot;
+      *(outbuffer + offset + 0) = (u_process_value_dot.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_process_value_dot.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_process_value_dot.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_process_value_dot.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_process_value_dot.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_process_value_dot.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_process_value_dot.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_process_value_dot.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->process_value_dot);
+      union {
+        double real;
+        uint64_t base;
+      } u_error;
+      u_error.real = this->error;
+      *(outbuffer + offset + 0) = (u_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->error);
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.real = this->time_step;
+      *(outbuffer + offset + 0) = (u_time_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_time_step.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_time_step.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_time_step.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_time_step.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->time_step);
+      union {
+        double real;
+        uint64_t base;
+      } u_command;
+      u_command.real = this->command;
+      *(outbuffer + offset + 0) = (u_command.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_command.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_command.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_command.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_command.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_command.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_command.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_command.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->command);
+      union {
+        double real;
+        uint64_t base;
+      } u_p;
+      u_p.real = this->p;
+      *(outbuffer + offset + 0) = (u_p.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_p.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_p.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_p.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_p.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_p.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_p.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_p.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->p);
+      union {
+        double real;
+        uint64_t base;
+      } u_i;
+      u_i.real = this->i;
+      *(outbuffer + offset + 0) = (u_i.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i);
+      union {
+        double real;
+        uint64_t base;
+      } u_d;
+      u_d.real = this->d;
+      *(outbuffer + offset + 0) = (u_d.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_d.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_d.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_d.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_d.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_d.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_d.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_d.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->d);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_clamp;
+      u_i_clamp.real = this->i_clamp;
+      *(outbuffer + offset + 0) = (u_i_clamp.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i_clamp.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i_clamp.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i_clamp.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i_clamp.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i_clamp.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i_clamp.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i_clamp.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i_clamp);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_set_point;
+      u_set_point.base = 0;
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->set_point = u_set_point.real;
+      offset += sizeof(this->set_point);
+      union {
+        double real;
+        uint64_t base;
+      } u_process_value;
+      u_process_value.base = 0;
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->process_value = u_process_value.real;
+      offset += sizeof(this->process_value);
+      union {
+        double real;
+        uint64_t base;
+      } u_process_value_dot;
+      u_process_value_dot.base = 0;
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->process_value_dot = u_process_value_dot.real;
+      offset += sizeof(this->process_value_dot);
+      union {
+        double real;
+        uint64_t base;
+      } u_error;
+      u_error.base = 0;
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->error = u_error.real;
+      offset += sizeof(this->error);
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.base = 0;
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->time_step = u_time_step.real;
+      offset += sizeof(this->time_step);
+      union {
+        double real;
+        uint64_t base;
+      } u_command;
+      u_command.base = 0;
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_command.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->command = u_command.real;
+      offset += sizeof(this->command);
+      union {
+        double real;
+        uint64_t base;
+      } u_p;
+      u_p.base = 0;
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_p.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->p = u_p.real;
+      offset += sizeof(this->p);
+      union {
+        double real;
+        uint64_t base;
+      } u_i;
+      u_i.base = 0;
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i = u_i.real;
+      offset += sizeof(this->i);
+      union {
+        double real;
+        uint64_t base;
+      } u_d;
+      u_d.base = 0;
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_d.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->d = u_d.real;
+      offset += sizeof(this->d);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_clamp;
+      u_i_clamp.base = 0;
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i_clamp = u_i_clamp.real;
+      offset += sizeof(this->i_clamp);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointControllerState"; };
+    const char * getMD5(){ return "c0d034a7bf20aeb1c37f3eccb7992b69"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTolerance.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTolerance.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,147 @@
+#ifndef _ROS_control_msgs_JointTolerance_h
+#define _ROS_control_msgs_JointTolerance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class JointTolerance : public ros::Msg
+  {
+    public:
+      const char* name;
+      double position;
+      double velocity;
+      double acceleration;
+
+    JointTolerance():
+      name(""),
+      position(0),
+      velocity(0),
+      acceleration(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_velocity;
+      u_velocity.real = this->velocity;
+      *(outbuffer + offset + 0) = (u_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_velocity.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_velocity.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_velocity.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_velocity.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_velocity.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->velocity);
+      union {
+        double real;
+        uint64_t base;
+      } u_acceleration;
+      u_acceleration.real = this->acceleration;
+      *(outbuffer + offset + 0) = (u_acceleration.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_acceleration.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_acceleration.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_acceleration.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_acceleration.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_acceleration.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_acceleration.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_acceleration.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->acceleration);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_velocity;
+      u_velocity.base = 0;
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->velocity = u_velocity.real;
+      offset += sizeof(this->velocity);
+      union {
+        double real;
+        uint64_t base;
+      } u_acceleration;
+      u_acceleration.base = 0;
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->acceleration = u_acceleration.real;
+      offset += sizeof(this->acceleration);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTolerance"; };
+    const char * getMD5(){ return "f544fe9c16cf04547e135dd6063ff5be"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_JointTrajectoryAction_h
+#define _ROS_control_msgs_JointTrajectoryAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/JointTrajectoryActionGoal.h"
+#include "control_msgs/JointTrajectoryActionResult.h"
+#include "control_msgs/JointTrajectoryActionFeedback.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryAction : public ros::Msg
+  {
+    public:
+      control_msgs::JointTrajectoryActionGoal action_goal;
+      control_msgs::JointTrajectoryActionResult action_result;
+      control_msgs::JointTrajectoryActionFeedback action_feedback;
+
+    JointTrajectoryAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryAction"; };
+    const char * getMD5(){ return "a04ba3ee8f6a2d0985a6aeaf23d9d7ad"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionFeedback_h
+#define _ROS_control_msgs_JointTrajectoryActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/JointTrajectoryFeedback.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::JointTrajectoryFeedback feedback;
+
+    JointTrajectoryActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionGoal_h
+#define _ROS_control_msgs_JointTrajectoryActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "control_msgs/JointTrajectoryGoal.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      control_msgs::JointTrajectoryGoal goal;
+
+    JointTrajectoryActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryActionGoal"; };
+    const char * getMD5(){ return "a99e83ef6185f9fdd7693efe99623a86"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionResult_h
+#define _ROS_control_msgs_JointTrajectoryActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/JointTrajectoryResult.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::JointTrajectoryResult result;
+
+    JointTrajectoryActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryActionResult"; };
+    const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryControllerState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryControllerState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,88 @@
+#ifndef _ROS_control_msgs_JointTrajectoryControllerState_h
+#define _ROS_control_msgs_JointTrajectoryControllerState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "trajectory_msgs/JointTrajectoryPoint.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryControllerState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      trajectory_msgs::JointTrajectoryPoint desired;
+      trajectory_msgs::JointTrajectoryPoint actual;
+      trajectory_msgs::JointTrajectoryPoint error;
+
+    JointTrajectoryControllerState():
+      header(),
+      joint_names_length(0), joint_names(NULL),
+      desired(),
+      actual(),
+      error()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      offset += this->desired.serialize(outbuffer + offset);
+      offset += this->actual.serialize(outbuffer + offset);
+      offset += this->error.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      offset += this->desired.deserialize(inbuffer + offset);
+      offset += this->actual.deserialize(inbuffer + offset);
+      offset += this->error.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryControllerState"; };
+    const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_JointTrajectoryFeedback_h
+#define _ROS_control_msgs_JointTrajectoryFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryFeedback : public ros::Msg
+  {
+    public:
+
+    JointTrajectoryFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,43 @@
+#ifndef _ROS_control_msgs_JointTrajectoryGoal_h
+#define _ROS_control_msgs_JointTrajectoryGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "trajectory_msgs/JointTrajectory.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryGoal : public ros::Msg
+  {
+    public:
+      trajectory_msgs::JointTrajectory trajectory;
+
+    JointTrajectoryGoal():
+      trajectory()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->trajectory.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->trajectory.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryGoal"; };
+    const char * getMD5(){ return "2a0eff76c870e8595636c2a562ca298e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/JointTrajectoryResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_JointTrajectoryResult_h
+#define _ROS_control_msgs_JointTrajectoryResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class JointTrajectoryResult : public ros::Msg
+  {
+    public:
+
+    JointTrajectoryResult()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointTrajectoryResult"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_PointHeadAction_h
+#define _ROS_control_msgs_PointHeadAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/PointHeadActionGoal.h"
+#include "control_msgs/PointHeadActionResult.h"
+#include "control_msgs/PointHeadActionFeedback.h"
+
+namespace control_msgs
+{
+
+  class PointHeadAction : public ros::Msg
+  {
+    public:
+      control_msgs::PointHeadActionGoal action_goal;
+      control_msgs::PointHeadActionResult action_result;
+      control_msgs::PointHeadActionFeedback action_feedback;
+
+    PointHeadAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadAction"; };
+    const char * getMD5(){ return "7252920f1243de1b741f14f214125371"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_PointHeadActionFeedback_h
+#define _ROS_control_msgs_PointHeadActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/PointHeadFeedback.h"
+
+namespace control_msgs
+{
+
+  class PointHeadActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::PointHeadFeedback feedback;
+
+    PointHeadActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadActionFeedback"; };
+    const char * getMD5(){ return "33c9244957176bbba97dd641119e8460"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_PointHeadActionGoal_h
+#define _ROS_control_msgs_PointHeadActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "control_msgs/PointHeadGoal.h"
+
+namespace control_msgs
+{
+
+  class PointHeadActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      control_msgs::PointHeadGoal goal;
+
+    PointHeadActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadActionGoal"; };
+    const char * getMD5(){ return "b53a8323d0ba7b310ba17a2d3a82a6b8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_PointHeadActionResult_h
+#define _ROS_control_msgs_PointHeadActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/PointHeadResult.h"
+
+namespace control_msgs
+{
+
+  class PointHeadActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::PointHeadResult result;
+
+    PointHeadActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadActionResult"; };
+    const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_control_msgs_PointHeadFeedback_h
+#define _ROS_control_msgs_PointHeadFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class PointHeadFeedback : public ros::Msg
+  {
+    public:
+      double pointing_angle_error;
+
+    PointHeadFeedback():
+      pointing_angle_error(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_pointing_angle_error;
+      u_pointing_angle_error.real = this->pointing_angle_error;
+      *(outbuffer + offset + 0) = (u_pointing_angle_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_pointing_angle_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_pointing_angle_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_pointing_angle_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_pointing_angle_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_pointing_angle_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_pointing_angle_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_pointing_angle_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->pointing_angle_error);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_pointing_angle_error;
+      u_pointing_angle_error.base = 0;
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_pointing_angle_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->pointing_angle_error = u_pointing_angle_error.real;
+      offset += sizeof(this->pointing_angle_error);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadFeedback"; };
+    const char * getMD5(){ return "cce80d27fd763682da8805a73316cab4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,118 @@
+#ifndef _ROS_control_msgs_PointHeadGoal_h
+#define _ROS_control_msgs_PointHeadGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/PointStamped.h"
+#include "geometry_msgs/Vector3.h"
+#include "ros/duration.h"
+
+namespace control_msgs
+{
+
+  class PointHeadGoal : public ros::Msg
+  {
+    public:
+      geometry_msgs::PointStamped target;
+      geometry_msgs::Vector3 pointing_axis;
+      const char* pointing_frame;
+      ros::Duration min_duration;
+      double max_velocity;
+
+    PointHeadGoal():
+      target(),
+      pointing_axis(),
+      pointing_frame(""),
+      min_duration(),
+      max_velocity(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->target.serialize(outbuffer + offset);
+      offset += this->pointing_axis.serialize(outbuffer + offset);
+      uint32_t length_pointing_frame = strlen(this->pointing_frame);
+      memcpy(outbuffer + offset, &length_pointing_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->pointing_frame, length_pointing_frame);
+      offset += length_pointing_frame;
+      *(outbuffer + offset + 0) = (this->min_duration.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->min_duration.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->min_duration.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->min_duration.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_duration.sec);
+      *(outbuffer + offset + 0) = (this->min_duration.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->min_duration.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->min_duration.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->min_duration.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_duration.nsec);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_velocity;
+      u_max_velocity.real = this->max_velocity;
+      *(outbuffer + offset + 0) = (u_max_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_velocity.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_velocity.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_velocity.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_velocity.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_velocity.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_velocity);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->target.deserialize(inbuffer + offset);
+      offset += this->pointing_axis.deserialize(inbuffer + offset);
+      uint32_t length_pointing_frame;
+      memcpy(&length_pointing_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_pointing_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_pointing_frame-1]=0;
+      this->pointing_frame = (char *)(inbuffer + offset-1);
+      offset += length_pointing_frame;
+      this->min_duration.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->min_duration.sec);
+      this->min_duration.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->min_duration.nsec);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_velocity;
+      u_max_velocity.base = 0;
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_velocity = u_max_velocity.real;
+      offset += sizeof(this->max_velocity);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadGoal"; };
+    const char * getMD5(){ return "8b92b1cd5e06c8a94c917dc3209a4c1d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/PointHeadResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_PointHeadResult_h
+#define _ROS_control_msgs_PointHeadResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class PointHeadResult : public ros::Msg
+  {
+    public:
+
+    PointHeadResult()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PointHeadResult"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/QueryCalibrationState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/QueryCalibrationState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,87 @@
+#ifndef _ROS_SERVICE_QueryCalibrationState_h
+#define _ROS_SERVICE_QueryCalibrationState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+static const char QUERYCALIBRATIONSTATE[] = "control_msgs/QueryCalibrationState";
+
+  class QueryCalibrationStateRequest : public ros::Msg
+  {
+    public:
+
+    QueryCalibrationStateRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return QUERYCALIBRATIONSTATE; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class QueryCalibrationStateResponse : public ros::Msg
+  {
+    public:
+      bool is_calibrated;
+
+    QueryCalibrationStateResponse():
+      is_calibrated(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_calibrated;
+      u_is_calibrated.real = this->is_calibrated;
+      *(outbuffer + offset + 0) = (u_is_calibrated.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_calibrated);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_calibrated;
+      u_is_calibrated.base = 0;
+      u_is_calibrated.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_calibrated = u_is_calibrated.real;
+      offset += sizeof(this->is_calibrated);
+     return offset;
+    }
+
+    const char * getType(){ return QUERYCALIBRATIONSTATE; };
+    const char * getMD5(){ return "28af3beedcb84986b8e470dc5470507d"; };
+
+  };
+
+  class QueryCalibrationState {
+    public:
+    typedef QueryCalibrationStateRequest Request;
+    typedef QueryCalibrationStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 control_msgs/QueryTrajectoryState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/QueryTrajectoryState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,266 @@
+#ifndef _ROS_SERVICE_QueryTrajectoryState_h
+#define _ROS_SERVICE_QueryTrajectoryState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace control_msgs
+{
+
+static const char QUERYTRAJECTORYSTATE[] = "control_msgs/QueryTrajectoryState";
+
+  class QueryTrajectoryStateRequest : public ros::Msg
+  {
+    public:
+      ros::Time time;
+
+    QueryTrajectoryStateRequest():
+      time()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time.sec);
+      *(outbuffer + offset + 0) = (this->time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time.sec);
+      this->time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return QUERYTRAJECTORYSTATE; };
+    const char * getMD5(){ return "556a4fb76023a469987922359d08a844"; };
+
+  };
+
+  class QueryTrajectoryStateResponse : public ros::Msg
+  {
+    public:
+      uint8_t name_length;
+      char* st_name;
+      char* * name;
+      uint8_t position_length;
+      double st_position;
+      double * position;
+      uint8_t velocity_length;
+      double st_velocity;
+      double * velocity;
+      uint8_t acceleration_length;
+      double st_acceleration;
+      double * acceleration;
+
+    QueryTrajectoryStateResponse():
+      name_length(0), name(NULL),
+      position_length(0), position(NULL),
+      velocity_length(0), velocity(NULL),
+      acceleration_length(0), acceleration(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset++) = position_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_positioni;
+      u_positioni.real = this->position[i];
+      *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position[i]);
+      }
+      *(outbuffer + offset++) = velocity_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < velocity_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_velocityi;
+      u_velocityi.real = this->velocity[i];
+      *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->velocity[i]);
+      }
+      *(outbuffer + offset++) = acceleration_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < acceleration_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_accelerationi;
+      u_accelerationi.real = this->acceleration[i];
+      *(outbuffer + offset + 0) = (u_accelerationi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_accelerationi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_accelerationi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_accelerationi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_accelerationi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_accelerationi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_accelerationi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_accelerationi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->acceleration[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint8_t position_lengthT = *(inbuffer + offset++);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      offset += 3;
+      position_length = position_lengthT;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_position;
+      u_st_position.base = 0;
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_position = u_st_position.real;
+      offset += sizeof(this->st_position);
+        memcpy( &(this->position[i]), &(this->st_position), sizeof(double));
+      }
+      uint8_t velocity_lengthT = *(inbuffer + offset++);
+      if(velocity_lengthT > velocity_length)
+        this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
+      offset += 3;
+      velocity_length = velocity_lengthT;
+      for( uint8_t i = 0; i < velocity_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_velocity;
+      u_st_velocity.base = 0;
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_velocity = u_st_velocity.real;
+      offset += sizeof(this->st_velocity);
+        memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double));
+      }
+      uint8_t acceleration_lengthT = *(inbuffer + offset++);
+      if(acceleration_lengthT > acceleration_length)
+        this->acceleration = (double*)realloc(this->acceleration, acceleration_lengthT * sizeof(double));
+      offset += 3;
+      acceleration_length = acceleration_lengthT;
+      for( uint8_t i = 0; i < acceleration_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_acceleration;
+      u_st_acceleration.base = 0;
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_acceleration = u_st_acceleration.real;
+      offset += sizeof(this->st_acceleration);
+        memcpy( &(this->acceleration[i]), &(this->st_acceleration), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return QUERYTRAJECTORYSTATE; };
+    const char * getMD5(){ return "1f1a6554ad060f44d013e71868403c1a"; };
+
+  };
+
+  class QueryTrajectoryState {
+    public:
+    typedef QueryTrajectoryStateRequest Request;
+    typedef QueryTrajectoryStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_SingleJointPositionAction_h
+#define _ROS_control_msgs_SingleJointPositionAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "control_msgs/SingleJointPositionActionGoal.h"
+#include "control_msgs/SingleJointPositionActionResult.h"
+#include "control_msgs/SingleJointPositionActionFeedback.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionAction : public ros::Msg
+  {
+    public:
+      control_msgs::SingleJointPositionActionGoal action_goal;
+      control_msgs::SingleJointPositionActionResult action_result;
+      control_msgs::SingleJointPositionActionFeedback action_feedback;
+
+    SingleJointPositionAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionAction"; };
+    const char * getMD5(){ return "c4a786b7d53e5d0983decf967a5a779e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionFeedback_h
+#define _ROS_control_msgs_SingleJointPositionActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/SingleJointPositionFeedback.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::SingleJointPositionFeedback feedback;
+
+    SingleJointPositionActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionActionFeedback"; };
+    const char * getMD5(){ return "3503b7cf8972f90d245850a5d8796cfa"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionGoal_h
+#define _ROS_control_msgs_SingleJointPositionActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "control_msgs/SingleJointPositionGoal.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      control_msgs::SingleJointPositionGoal goal;
+
+    SingleJointPositionActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionActionGoal"; };
+    const char * getMD5(){ return "4b0d3d091471663e17749c1d0db90f61"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionResult_h
+#define _ROS_control_msgs_SingleJointPositionActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "control_msgs/SingleJointPositionResult.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      control_msgs::SingleJointPositionResult result;
+
+    SingleJointPositionActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionActionResult"; };
+    const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,136 @@
+#ifndef _ROS_control_msgs_SingleJointPositionFeedback_h
+#define _ROS_control_msgs_SingleJointPositionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double position;
+      double velocity;
+      double error;
+
+    SingleJointPositionFeedback():
+      header(),
+      position(0),
+      velocity(0),
+      error(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_velocity;
+      u_velocity.real = this->velocity;
+      *(outbuffer + offset + 0) = (u_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_velocity.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_velocity.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_velocity.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_velocity.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_velocity.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->velocity);
+      union {
+        double real;
+        uint64_t base;
+      } u_error;
+      u_error.real = this->error;
+      *(outbuffer + offset + 0) = (u_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->error);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      union {
+        double real;
+        uint64_t base;
+      } u_velocity;
+      u_velocity.base = 0;
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->velocity = u_velocity.real;
+      offset += sizeof(this->velocity);
+      union {
+        double real;
+        uint64_t base;
+      } u_error;
+      u_error.base = 0;
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->error = u_error.real;
+      offset += sizeof(this->error);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionFeedback"; };
+    const char * getMD5(){ return "8cee65610a3d08e0a1bded82f146f1fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,123 @@
+#ifndef _ROS_control_msgs_SingleJointPositionGoal_h
+#define _ROS_control_msgs_SingleJointPositionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionGoal : public ros::Msg
+  {
+    public:
+      double position;
+      ros::Duration min_duration;
+      double max_velocity;
+
+    SingleJointPositionGoal():
+      position(0),
+      min_duration(),
+      max_velocity(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.real = this->position;
+      *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position);
+      *(outbuffer + offset + 0) = (this->min_duration.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->min_duration.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->min_duration.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->min_duration.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_duration.sec);
+      *(outbuffer + offset + 0) = (this->min_duration.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->min_duration.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->min_duration.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->min_duration.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_duration.nsec);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_velocity;
+      u_max_velocity.real = this->max_velocity;
+      *(outbuffer + offset + 0) = (u_max_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_velocity.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_velocity.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_velocity.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_velocity.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_velocity.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_velocity);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_position;
+      u_position.base = 0;
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position = u_position.real;
+      offset += sizeof(this->position);
+      this->min_duration.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->min_duration.sec);
+      this->min_duration.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->min_duration.nsec);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_velocity;
+      u_max_velocity.base = 0;
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_velocity = u_max_velocity.real;
+      offset += sizeof(this->max_velocity);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionGoal"; };
+    const char * getMD5(){ return "fbaaa562a23a013fd5053e5f72cbb35c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 control_msgs/SingleJointPositionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_SingleJointPositionResult_h
+#define _ROS_control_msgs_SingleJointPositionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+  class SingleJointPositionResult : public ros::Msg
+  {
+    public:
+
+    SingleJointPositionResult()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/SingleJointPositionResult"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 diagnostic_msgs/DiagnosticArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/DiagnosticArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_diagnostic_msgs_DiagnosticArray_h
+#define _ROS_diagnostic_msgs_DiagnosticArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
+
+namespace diagnostic_msgs
+{
+
+  class DiagnosticArray : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t status_length;
+      diagnostic_msgs::DiagnosticStatus st_status;
+      diagnostic_msgs::DiagnosticStatus * status;
+
+    DiagnosticArray():
+      header(),
+      status_length(0), status(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = status_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->status[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t status_lengthT = *(inbuffer + offset++);
+      if(status_lengthT > status_length)
+        this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
+      offset += 3;
+      status_length = status_lengthT;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->st_status.deserialize(inbuffer + offset);
+        memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; };
+    const char * getMD5(){ return "60810da900de1dd6ddd437c3503511da"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 diagnostic_msgs/DiagnosticStatus.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/DiagnosticStatus.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,128 @@
+#ifndef _ROS_diagnostic_msgs_DiagnosticStatus_h
+#define _ROS_diagnostic_msgs_DiagnosticStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "diagnostic_msgs/KeyValue.h"
+
+namespace diagnostic_msgs
+{
+
+  class DiagnosticStatus : public ros::Msg
+  {
+    public:
+      int8_t level;
+      const char* name;
+      const char* message;
+      const char* hardware_id;
+      uint8_t values_length;
+      diagnostic_msgs::KeyValue st_values;
+      diagnostic_msgs::KeyValue * values;
+      enum { OK = 0 };
+      enum { WARN = 1 };
+      enum { ERROR = 2 };
+      enum { STALE = 3 };
+
+    DiagnosticStatus():
+      level(0),
+      name(""),
+      message(""),
+      hardware_id(""),
+      values_length(0), values(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_level;
+      u_level.real = this->level;
+      *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->level);
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_message = strlen(this->message);
+      memcpy(outbuffer + offset, &length_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->message, length_message);
+      offset += length_message;
+      uint32_t length_hardware_id = strlen(this->hardware_id);
+      memcpy(outbuffer + offset, &length_hardware_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->hardware_id, length_hardware_id);
+      offset += length_hardware_id;
+      *(outbuffer + offset++) = values_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < values_length; i++){
+      offset += this->values[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_level;
+      u_level.base = 0;
+      u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->level = u_level.real;
+      offset += sizeof(this->level);
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_message;
+      memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_message-1]=0;
+      this->message = (char *)(inbuffer + offset-1);
+      offset += length_message;
+      uint32_t length_hardware_id;
+      memcpy(&length_hardware_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_hardware_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_hardware_id-1]=0;
+      this->hardware_id = (char *)(inbuffer + offset-1);
+      offset += length_hardware_id;
+      uint8_t values_lengthT = *(inbuffer + offset++);
+      if(values_lengthT > values_length)
+        this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue));
+      offset += 3;
+      values_length = values_lengthT;
+      for( uint8_t i = 0; i < values_length; i++){
+      offset += this->st_values.deserialize(inbuffer + offset);
+        memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; };
+    const char * getMD5(){ return "d0ce08bc6e5ba34c7754f563a9cabaf1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 diagnostic_msgs/KeyValue.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/KeyValue.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_diagnostic_msgs_KeyValue_h
+#define _ROS_diagnostic_msgs_KeyValue_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace diagnostic_msgs
+{
+
+  class KeyValue : public ros::Msg
+  {
+    public:
+      const char* key;
+      const char* value;
+
+    KeyValue():
+      key(""),
+      value("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_key = strlen(this->key);
+      memcpy(outbuffer + offset, &length_key, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->key, length_key);
+      offset += length_key;
+      uint32_t length_value = strlen(this->value);
+      memcpy(outbuffer + offset, &length_value, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->value, length_value);
+      offset += length_value;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_key;
+      memcpy(&length_key, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_key; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_key-1]=0;
+      this->key = (char *)(inbuffer + offset-1);
+      offset += length_key;
+      uint32_t length_value;
+      memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_value; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_value-1]=0;
+      this->value = (char *)(inbuffer + offset-1);
+      offset += length_value;
+     return offset;
+    }
+
+    const char * getType(){ return "diagnostic_msgs/KeyValue"; };
+    const char * getMD5(){ return "cf57fdc6617a881a88c16e768132149c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 diagnostic_msgs/SelfTest.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/SelfTest.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,124 @@
+#ifndef _ROS_SERVICE_SelfTest_h
+#define _ROS_SERVICE_SelfTest_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
+
+namespace diagnostic_msgs
+{
+
+static const char SELFTEST[] = "diagnostic_msgs/SelfTest";
+
+  class SelfTestRequest : public ros::Msg
+  {
+    public:
+
+    SelfTestRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SELFTEST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SelfTestResponse : public ros::Msg
+  {
+    public:
+      const char* id;
+      int8_t passed;
+      uint8_t status_length;
+      diagnostic_msgs::DiagnosticStatus st_status;
+      diagnostic_msgs::DiagnosticStatus * status;
+
+    SelfTestResponse():
+      id(""),
+      passed(0),
+      status_length(0), status(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_id = strlen(this->id);
+      memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->id, length_id);
+      offset += length_id;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_passed;
+      u_passed.real = this->passed;
+      *(outbuffer + offset + 0) = (u_passed.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->passed);
+      *(outbuffer + offset++) = status_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->status[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_id;
+      memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_id-1]=0;
+      this->id = (char *)(inbuffer + offset-1);
+      offset += length_id;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_passed;
+      u_passed.base = 0;
+      u_passed.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->passed = u_passed.real;
+      offset += sizeof(this->passed);
+      uint8_t status_lengthT = *(inbuffer + offset++);
+      if(status_lengthT > status_length)
+        this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
+      offset += 3;
+      status_length = status_lengthT;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->st_status.deserialize(inbuffer + offset);
+        memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return SELFTEST; };
+    const char * getMD5(){ return "ac21b1bab7ab17546986536c22eb34e9"; };
+
+  };
+
+  class SelfTest {
+    public:
+    typedef SelfTestRequest Request;
+    typedef SelfTestResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 driver_base/ConfigString.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/driver_base/ConfigString.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_driver_base_ConfigString_h
+#define _ROS_driver_base_ConfigString_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace driver_base
+{
+
+  class ConfigString : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* value;
+
+    ConfigString():
+      name(""),
+      value("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_value = strlen(this->value);
+      memcpy(outbuffer + offset, &length_value, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->value, length_value);
+      offset += length_value;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_value;
+      memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_value; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_value-1]=0;
+      this->value = (char *)(inbuffer + offset-1);
+      offset += length_value;
+     return offset;
+    }
+
+    const char * getType(){ return "driver_base/ConfigString"; };
+    const char * getMD5(){ return "bc6ccc4a57f61779c8eaae61e9f422e0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 driver_base/ConfigValue.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/driver_base/ConfigValue.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,85 @@
+#ifndef _ROS_driver_base_ConfigValue_h
+#define _ROS_driver_base_ConfigValue_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace driver_base
+{
+
+  class ConfigValue : public ros::Msg
+  {
+    public:
+      const char* name;
+      double value;
+
+    ConfigValue():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_value;
+      u_value.real = this->value;
+      *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_value.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_value.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_value.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_value.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->value);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_value;
+      u_value.base = 0;
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->value = u_value.real;
+      offset += sizeof(this->value);
+     return offset;
+    }
+
+    const char * getType(){ return "driver_base/ConfigValue"; };
+    const char * getMD5(){ return "d8512f27253c0f65f928a67c329cd658"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 driver_base/SensorLevels.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/driver_base/SensorLevels.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,41 @@
+#ifndef _ROS_driver_base_SensorLevels_h
+#define _ROS_driver_base_SensorLevels_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace driver_base
+{
+
+  class SensorLevels : public ros::Msg
+  {
+    public:
+      enum { RECONFIGURE_CLOSE =  3   };
+      enum { RECONFIGURE_STOP =  1   };
+      enum { RECONFIGURE_RUNNING =  0  };
+
+    SensorLevels()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "driver_base/SensorLevels"; };
+    const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 duration.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/duration.cpp	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,81 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <math.h>
+#include "ros/duration.h"
+
+namespace ros
+{
+  void normalizeSecNSecSigned(int32_t &sec, int32_t &nsec)
+  {
+    int32_t nsec_part = nsec;
+    int32_t sec_part = sec;
+
+    while (nsec_part > 1000000000L)
+    {
+      nsec_part -= 1000000000L;
+      ++sec_part;
+    }
+    while (nsec_part < 0)
+    {
+      nsec_part += 1000000000L;
+      --sec_part;
+    }
+    sec = sec_part;
+    nsec = nsec_part;
+  }
+
+  Duration& Duration::operator+=(const Duration &rhs)
+  {
+    sec += rhs.sec;
+    nsec += rhs.nsec;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+  Duration& Duration::operator-=(const Duration &rhs){
+    sec += -rhs.sec;
+    nsec += -rhs.nsec;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+  Duration& Duration::operator*=(double scale){
+    sec *= scale;
+    nsec *= scale;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+}
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/BoolParameter.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/BoolParameter.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,71 @@
+#ifndef _ROS_dynamic_reconfigure_BoolParameter_h
+#define _ROS_dynamic_reconfigure_BoolParameter_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class BoolParameter : public ros::Msg
+  {
+    public:
+      const char* name;
+      bool value;
+
+    BoolParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        bool real;
+        uint8_t base;
+      } u_value;
+      u_value.real = this->value;
+      *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->value);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        bool real;
+        uint8_t base;
+      } u_value;
+      u_value.base = 0;
+      u_value.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->value = u_value.real;
+      offset += sizeof(this->value);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/BoolParameter"; };
+    const char * getMD5(){ return "23f05028c1a699fb83e22401228c3a9e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/Config.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Config.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,143 @@
+#ifndef _ROS_dynamic_reconfigure_Config_h
+#define _ROS_dynamic_reconfigure_Config_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "dynamic_reconfigure/BoolParameter.h"
+#include "dynamic_reconfigure/IntParameter.h"
+#include "dynamic_reconfigure/StrParameter.h"
+#include "dynamic_reconfigure/DoubleParameter.h"
+#include "dynamic_reconfigure/GroupState.h"
+
+namespace dynamic_reconfigure
+{
+
+  class Config : public ros::Msg
+  {
+    public:
+      uint8_t bools_length;
+      dynamic_reconfigure::BoolParameter st_bools;
+      dynamic_reconfigure::BoolParameter * bools;
+      uint8_t ints_length;
+      dynamic_reconfigure::IntParameter st_ints;
+      dynamic_reconfigure::IntParameter * ints;
+      uint8_t strs_length;
+      dynamic_reconfigure::StrParameter st_strs;
+      dynamic_reconfigure::StrParameter * strs;
+      uint8_t doubles_length;
+      dynamic_reconfigure::DoubleParameter st_doubles;
+      dynamic_reconfigure::DoubleParameter * doubles;
+      uint8_t groups_length;
+      dynamic_reconfigure::GroupState st_groups;
+      dynamic_reconfigure::GroupState * groups;
+
+    Config():
+      bools_length(0), bools(NULL),
+      ints_length(0), ints(NULL),
+      strs_length(0), strs(NULL),
+      doubles_length(0), doubles(NULL),
+      groups_length(0), groups(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = bools_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < bools_length; i++){
+      offset += this->bools[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = ints_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < ints_length; i++){
+      offset += this->ints[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = strs_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < strs_length; i++){
+      offset += this->strs[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = doubles_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < doubles_length; i++){
+      offset += this->doubles[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = groups_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < groups_length; i++){
+      offset += this->groups[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t bools_lengthT = *(inbuffer + offset++);
+      if(bools_lengthT > bools_length)
+        this->bools = (dynamic_reconfigure::BoolParameter*)realloc(this->bools, bools_lengthT * sizeof(dynamic_reconfigure::BoolParameter));
+      offset += 3;
+      bools_length = bools_lengthT;
+      for( uint8_t i = 0; i < bools_length; i++){
+      offset += this->st_bools.deserialize(inbuffer + offset);
+        memcpy( &(this->bools[i]), &(this->st_bools), sizeof(dynamic_reconfigure::BoolParameter));
+      }
+      uint8_t ints_lengthT = *(inbuffer + offset++);
+      if(ints_lengthT > ints_length)
+        this->ints = (dynamic_reconfigure::IntParameter*)realloc(this->ints, ints_lengthT * sizeof(dynamic_reconfigure::IntParameter));
+      offset += 3;
+      ints_length = ints_lengthT;
+      for( uint8_t i = 0; i < ints_length; i++){
+      offset += this->st_ints.deserialize(inbuffer + offset);
+        memcpy( &(this->ints[i]), &(this->st_ints), sizeof(dynamic_reconfigure::IntParameter));
+      }
+      uint8_t strs_lengthT = *(inbuffer + offset++);
+      if(strs_lengthT > strs_length)
+        this->strs = (dynamic_reconfigure::StrParameter*)realloc(this->strs, strs_lengthT * sizeof(dynamic_reconfigure::StrParameter));
+      offset += 3;
+      strs_length = strs_lengthT;
+      for( uint8_t i = 0; i < strs_length; i++){
+      offset += this->st_strs.deserialize(inbuffer + offset);
+        memcpy( &(this->strs[i]), &(this->st_strs), sizeof(dynamic_reconfigure::StrParameter));
+      }
+      uint8_t doubles_lengthT = *(inbuffer + offset++);
+      if(doubles_lengthT > doubles_length)
+        this->doubles = (dynamic_reconfigure::DoubleParameter*)realloc(this->doubles, doubles_lengthT * sizeof(dynamic_reconfigure::DoubleParameter));
+      offset += 3;
+      doubles_length = doubles_lengthT;
+      for( uint8_t i = 0; i < doubles_length; i++){
+      offset += this->st_doubles.deserialize(inbuffer + offset);
+        memcpy( &(this->doubles[i]), &(this->st_doubles), sizeof(dynamic_reconfigure::DoubleParameter));
+      }
+      uint8_t groups_lengthT = *(inbuffer + offset++);
+      if(groups_lengthT > groups_length)
+        this->groups = (dynamic_reconfigure::GroupState*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::GroupState));
+      offset += 3;
+      groups_length = groups_lengthT;
+      for( uint8_t i = 0; i < groups_length; i++){
+      offset += this->st_groups.deserialize(inbuffer + offset);
+        memcpy( &(this->groups[i]), &(this->st_groups), sizeof(dynamic_reconfigure::GroupState));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/Config"; };
+    const char * getMD5(){ return "958f16a05573709014982821e6822580"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/ConfigDescription.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/ConfigDescription.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,72 @@
+#ifndef _ROS_dynamic_reconfigure_ConfigDescription_h
+#define _ROS_dynamic_reconfigure_ConfigDescription_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "dynamic_reconfigure/Group.h"
+#include "dynamic_reconfigure/Config.h"
+
+namespace dynamic_reconfigure
+{
+
+  class ConfigDescription : public ros::Msg
+  {
+    public:
+      uint8_t groups_length;
+      dynamic_reconfigure::Group st_groups;
+      dynamic_reconfigure::Group * groups;
+      dynamic_reconfigure::Config max;
+      dynamic_reconfigure::Config min;
+      dynamic_reconfigure::Config dflt;
+
+    ConfigDescription():
+      groups_length(0), groups(NULL),
+      max(),
+      min(),
+      dflt()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = groups_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < groups_length; i++){
+      offset += this->groups[i].serialize(outbuffer + offset);
+      }
+      offset += this->max.serialize(outbuffer + offset);
+      offset += this->min.serialize(outbuffer + offset);
+      offset += this->dflt.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t groups_lengthT = *(inbuffer + offset++);
+      if(groups_lengthT > groups_length)
+        this->groups = (dynamic_reconfigure::Group*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::Group));
+      offset += 3;
+      groups_length = groups_lengthT;
+      for( uint8_t i = 0; i < groups_length; i++){
+      offset += this->st_groups.deserialize(inbuffer + offset);
+        memcpy( &(this->groups[i]), &(this->st_groups), sizeof(dynamic_reconfigure::Group));
+      }
+      offset += this->max.deserialize(inbuffer + offset);
+      offset += this->min.deserialize(inbuffer + offset);
+      offset += this->dflt.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/ConfigDescription"; };
+    const char * getMD5(){ return "757ce9d44ba8ddd801bb30bc456f946f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/DoubleParameter.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/DoubleParameter.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,85 @@
+#ifndef _ROS_dynamic_reconfigure_DoubleParameter_h
+#define _ROS_dynamic_reconfigure_DoubleParameter_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class DoubleParameter : public ros::Msg
+  {
+    public:
+      const char* name;
+      double value;
+
+    DoubleParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_value;
+      u_value.real = this->value;
+      *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_value.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_value.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_value.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_value.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->value);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_value;
+      u_value.base = 0;
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_value.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->value = u_value.real;
+      offset += sizeof(this->value);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/DoubleParameter"; };
+    const char * getMD5(){ return "d8512f27253c0f65f928a67c329cd658"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/Group.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Group.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,137 @@
+#ifndef _ROS_dynamic_reconfigure_Group_h
+#define _ROS_dynamic_reconfigure_Group_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "dynamic_reconfigure/ParamDescription.h"
+
+namespace dynamic_reconfigure
+{
+
+  class Group : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* type;
+      uint8_t parameters_length;
+      dynamic_reconfigure::ParamDescription st_parameters;
+      dynamic_reconfigure::ParamDescription * parameters;
+      int32_t parent;
+      int32_t id;
+
+    Group():
+      name(""),
+      type(""),
+      parameters_length(0), parameters(NULL),
+      parent(0),
+      id(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      memcpy(outbuffer + offset, &length_type, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      *(outbuffer + offset++) = parameters_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < parameters_length; i++){
+      offset += this->parameters[i].serialize(outbuffer + offset);
+      }
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_parent;
+      u_parent.real = this->parent;
+      *(outbuffer + offset + 0) = (u_parent.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_parent.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_parent.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_parent.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->parent);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.real = this->id;
+      *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->id);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_type;
+      memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_type-1]=0;
+      this->type = (char *)(inbuffer + offset-1);
+      offset += length_type;
+      uint8_t parameters_lengthT = *(inbuffer + offset++);
+      if(parameters_lengthT > parameters_length)
+        this->parameters = (dynamic_reconfigure::ParamDescription*)realloc(this->parameters, parameters_lengthT * sizeof(dynamic_reconfigure::ParamDescription));
+      offset += 3;
+      parameters_length = parameters_lengthT;
+      for( uint8_t i = 0; i < parameters_length; i++){
+      offset += this->st_parameters.deserialize(inbuffer + offset);
+        memcpy( &(this->parameters[i]), &(this->st_parameters), sizeof(dynamic_reconfigure::ParamDescription));
+      }
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_parent;
+      u_parent.base = 0;
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->parent = u_parent.real;
+      offset += sizeof(this->parent);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.base = 0;
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->id = u_id.real;
+      offset += sizeof(this->id);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/Group"; };
+    const char * getMD5(){ return "9e8cd9e9423c94823db3614dd8b1cf7a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/GroupState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/GroupState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,117 @@
+#ifndef _ROS_dynamic_reconfigure_GroupState_h
+#define _ROS_dynamic_reconfigure_GroupState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class GroupState : public ros::Msg
+  {
+    public:
+      const char* name;
+      bool state;
+      int32_t id;
+      int32_t parent;
+
+    GroupState():
+      name(""),
+      state(0),
+      id(0),
+      parent(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        bool real;
+        uint8_t base;
+      } u_state;
+      u_state.real = this->state;
+      *(outbuffer + offset + 0) = (u_state.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->state);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.real = this->id;
+      *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_parent;
+      u_parent.real = this->parent;
+      *(outbuffer + offset + 0) = (u_parent.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_parent.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_parent.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_parent.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->parent);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        bool real;
+        uint8_t base;
+      } u_state;
+      u_state.base = 0;
+      u_state.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->state = u_state.real;
+      offset += sizeof(this->state);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.base = 0;
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->id = u_id.real;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_parent;
+      u_parent.base = 0;
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_parent.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->parent = u_parent.real;
+      offset += sizeof(this->parent);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/GroupState"; };
+    const char * getMD5(){ return "a2d87f51dc22930325041a2f8b1571f8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/IntParameter.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/IntParameter.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_dynamic_reconfigure_IntParameter_h
+#define _ROS_dynamic_reconfigure_IntParameter_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class IntParameter : public ros::Msg
+  {
+    public:
+      const char* name;
+      int32_t value;
+
+    IntParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_value;
+      u_value.real = this->value;
+      *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->value);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_value;
+      u_value.base = 0;
+      u_value.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_value.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_value.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_value.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->value = u_value.real;
+      offset += sizeof(this->value);
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/IntParameter"; };
+    const char * getMD5(){ return "65fedc7a0cbfb8db035e46194a350bf1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/ParamDescription.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/ParamDescription.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,114 @@
+#ifndef _ROS_dynamic_reconfigure_ParamDescription_h
+#define _ROS_dynamic_reconfigure_ParamDescription_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class ParamDescription : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* type;
+      uint32_t level;
+      const char* description;
+      const char* edit_method;
+
+    ParamDescription():
+      name(""),
+      type(""),
+      level(0),
+      description(""),
+      edit_method("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      memcpy(outbuffer + offset, &length_type, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->level >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->level >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->level >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->level);
+      uint32_t length_description = strlen(this->description);
+      memcpy(outbuffer + offset, &length_description, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->description, length_description);
+      offset += length_description;
+      uint32_t length_edit_method = strlen(this->edit_method);
+      memcpy(outbuffer + offset, &length_edit_method, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->edit_method, length_edit_method);
+      offset += length_edit_method;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_type;
+      memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_type-1]=0;
+      this->type = (char *)(inbuffer + offset-1);
+      offset += length_type;
+      this->level =  ((uint32_t) (*(inbuffer + offset)));
+      this->level |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->level |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->level |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->level);
+      uint32_t length_description;
+      memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_description; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_description-1]=0;
+      this->description = (char *)(inbuffer + offset-1);
+      offset += length_description;
+      uint32_t length_edit_method;
+      memcpy(&length_edit_method, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_edit_method; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_edit_method-1]=0;
+      this->edit_method = (char *)(inbuffer + offset-1);
+      offset += length_edit_method;
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/ParamDescription"; };
+    const char * getMD5(){ return "7434fcb9348c13054e0c3b267c8cb34d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/Reconfigure.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Reconfigure.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,79 @@
+#ifndef _ROS_SERVICE_Reconfigure_h
+#define _ROS_SERVICE_Reconfigure_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "dynamic_reconfigure/Config.h"
+
+namespace dynamic_reconfigure
+{
+
+static const char RECONFIGURE[] = "dynamic_reconfigure/Reconfigure";
+
+  class ReconfigureRequest : public ros::Msg
+  {
+    public:
+      dynamic_reconfigure::Config config;
+
+    ReconfigureRequest():
+      config()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->config.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->config.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return RECONFIGURE; };
+    const char * getMD5(){ return "ac41a77620a4a0348b7001641796a8a1"; };
+
+  };
+
+  class ReconfigureResponse : public ros::Msg
+  {
+    public:
+      dynamic_reconfigure::Config config;
+
+    ReconfigureResponse():
+      config()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->config.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->config.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return RECONFIGURE; };
+    const char * getMD5(){ return "ac41a77620a4a0348b7001641796a8a1"; };
+
+  };
+
+  class Reconfigure {
+    public:
+    typedef ReconfigureRequest Request;
+    typedef ReconfigureResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/SensorLevels.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/SensorLevels.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,41 @@
+#ifndef _ROS_dynamic_reconfigure_SensorLevels_h
+#define _ROS_dynamic_reconfigure_SensorLevels_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class SensorLevels : public ros::Msg
+  {
+    public:
+      enum { RECONFIGURE_CLOSE =  3   };
+      enum { RECONFIGURE_STOP =  1   };
+      enum { RECONFIGURE_RUNNING =  0  };
+
+    SensorLevels()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/SensorLevels"; };
+    const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 dynamic_reconfigure/StrParameter.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/StrParameter.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_dynamic_reconfigure_StrParameter_h
+#define _ROS_dynamic_reconfigure_StrParameter_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace dynamic_reconfigure
+{
+
+  class StrParameter : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* value;
+
+    StrParameter():
+      name(""),
+      value("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_value = strlen(this->value);
+      memcpy(outbuffer + offset, &length_value, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->value, length_value);
+      offset += length_value;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_value;
+      memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_value; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_value-1]=0;
+      this->value = (char *)(inbuffer + offset-1);
+      offset += length_value;
+     return offset;
+    }
+
+    const char * getType(){ return "dynamic_reconfigure/StrParameter"; };
+    const char * getMD5(){ return "bc6ccc4a57f61779c8eaae61e9f422e0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ApplyBodyWrench.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ApplyBodyWrench.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,191 @@
+#ifndef _ROS_SERVICE_ApplyBodyWrench_h
+#define _ROS_SERVICE_ApplyBodyWrench_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+#include "geometry_msgs/Wrench.h"
+#include "ros/time.h"
+#include "geometry_msgs/Point.h"
+
+namespace gazebo_msgs
+{
+
+static const char APPLYBODYWRENCH[] = "gazebo_msgs/ApplyBodyWrench";
+
+  class ApplyBodyWrenchRequest : public ros::Msg
+  {
+    public:
+      const char* body_name;
+      const char* reference_frame;
+      geometry_msgs::Point reference_point;
+      geometry_msgs::Wrench wrench;
+      ros::Time start_time;
+      ros::Duration duration;
+
+    ApplyBodyWrenchRequest():
+      body_name(""),
+      reference_frame(""),
+      reference_point(),
+      wrench(),
+      start_time(),
+      duration()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_body_name = strlen(this->body_name);
+      memcpy(outbuffer + offset, &length_body_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->body_name, length_body_name);
+      offset += length_body_name;
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
+      offset += length_reference_frame;
+      offset += this->reference_point.serialize(outbuffer + offset);
+      offset += this->wrench.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->start_time.sec);
+      *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->start_time.nsec);
+      *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->duration.sec);
+      *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->duration.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_body_name;
+      memcpy(&length_body_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_body_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_body_name-1]=0;
+      this->body_name = (char *)(inbuffer + offset-1);
+      offset += length_body_name;
+      uint32_t length_reference_frame;
+      memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_reference_frame-1]=0;
+      this->reference_frame = (char *)(inbuffer + offset-1);
+      offset += length_reference_frame;
+      offset += this->reference_point.deserialize(inbuffer + offset);
+      offset += this->wrench.deserialize(inbuffer + offset);
+      this->start_time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->start_time.sec);
+      this->start_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->start_time.nsec);
+      this->duration.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->duration.sec);
+      this->duration.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->duration.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return APPLYBODYWRENCH; };
+    const char * getMD5(){ return "e37e6adf97eba5095baa77dffb71e5bd"; };
+
+  };
+
+  class ApplyBodyWrenchResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    ApplyBodyWrenchResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return APPLYBODYWRENCH; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class ApplyBodyWrench {
+    public:
+    typedef ApplyBodyWrenchRequest Request;
+    typedef ApplyBodyWrenchResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ApplyJointEffort.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ApplyJointEffort.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,196 @@
+#ifndef _ROS_SERVICE_ApplyJointEffort_h
+#define _ROS_SERVICE_ApplyJointEffort_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+#include "ros/time.h"
+
+namespace gazebo_msgs
+{
+
+static const char APPLYJOINTEFFORT[] = "gazebo_msgs/ApplyJointEffort";
+
+  class ApplyJointEffortRequest : public ros::Msg
+  {
+    public:
+      const char* joint_name;
+      double effort;
+      ros::Time start_time;
+      ros::Duration duration;
+
+    ApplyJointEffortRequest():
+      joint_name(""),
+      effort(0),
+      start_time(),
+      duration()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_name, length_joint_name);
+      offset += length_joint_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.real = this->effort;
+      *(outbuffer + offset + 0) = (u_effort.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_effort.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_effort.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_effort.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_effort.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_effort.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_effort.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_effort.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->effort);
+      *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->start_time.sec);
+      *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->start_time.nsec);
+      *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->duration.sec);
+      *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->duration.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_joint_name;
+      memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_joint_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_joint_name-1]=0;
+      this->joint_name = (char *)(inbuffer + offset-1);
+      offset += length_joint_name;
+      union {
+        double real;
+        uint64_t base;
+      } u_effort;
+      u_effort.base = 0;
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->effort = u_effort.real;
+      offset += sizeof(this->effort);
+      this->start_time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->start_time.sec);
+      this->start_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->start_time.nsec);
+      this->duration.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->duration.sec);
+      this->duration.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->duration.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return APPLYJOINTEFFORT; };
+    const char * getMD5(){ return "2c3396ab9af67a509ecd2167a8fe41a2"; };
+
+  };
+
+  class ApplyJointEffortResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    ApplyJointEffortResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return APPLYJOINTEFFORT; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class ApplyJointEffort {
+    public:
+    typedef ApplyJointEffortRequest Request;
+    typedef ApplyJointEffortResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/BodyRequest.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/BodyRequest.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_BodyRequest_h
+#define _ROS_SERVICE_BodyRequest_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char BODYREQUEST[] = "gazebo_msgs/BodyRequest";
+
+  class BodyRequestRequest : public ros::Msg
+  {
+    public:
+      const char* body_name;
+
+    BodyRequestRequest():
+      body_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_body_name = strlen(this->body_name);
+      memcpy(outbuffer + offset, &length_body_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->body_name, length_body_name);
+      offset += length_body_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_body_name;
+      memcpy(&length_body_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_body_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_body_name-1]=0;
+      this->body_name = (char *)(inbuffer + offset-1);
+      offset += length_body_name;
+     return offset;
+    }
+
+    const char * getType(){ return BODYREQUEST; };
+    const char * getMD5(){ return "5eade9afe7f232d78005bd0cafeab755"; };
+
+  };
+
+  class BodyRequestResponse : public ros::Msg
+  {
+    public:
+
+    BodyRequestResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return BODYREQUEST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class BodyRequest {
+    public:
+    typedef BodyRequestRequest Request;
+    typedef BodyRequestResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ContactState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ContactState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,199 @@
+#ifndef _ROS_gazebo_msgs_ContactState_h
+#define _ROS_gazebo_msgs_ContactState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Wrench.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace gazebo_msgs
+{
+
+  class ContactState : public ros::Msg
+  {
+    public:
+      const char* info;
+      const char* collision1_name;
+      const char* collision2_name;
+      uint8_t wrenches_length;
+      geometry_msgs::Wrench st_wrenches;
+      geometry_msgs::Wrench * wrenches;
+      geometry_msgs::Wrench total_wrench;
+      uint8_t contact_positions_length;
+      geometry_msgs::Vector3 st_contact_positions;
+      geometry_msgs::Vector3 * contact_positions;
+      uint8_t contact_normals_length;
+      geometry_msgs::Vector3 st_contact_normals;
+      geometry_msgs::Vector3 * contact_normals;
+      uint8_t depths_length;
+      double st_depths;
+      double * depths;
+
+    ContactState():
+      info(""),
+      collision1_name(""),
+      collision2_name(""),
+      wrenches_length(0), wrenches(NULL),
+      total_wrench(),
+      contact_positions_length(0), contact_positions(NULL),
+      contact_normals_length(0), contact_normals(NULL),
+      depths_length(0), depths(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_info = strlen(this->info);
+      memcpy(outbuffer + offset, &length_info, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->info, length_info);
+      offset += length_info;
+      uint32_t length_collision1_name = strlen(this->collision1_name);
+      memcpy(outbuffer + offset, &length_collision1_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->collision1_name, length_collision1_name);
+      offset += length_collision1_name;
+      uint32_t length_collision2_name = strlen(this->collision2_name);
+      memcpy(outbuffer + offset, &length_collision2_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->collision2_name, length_collision2_name);
+      offset += length_collision2_name;
+      *(outbuffer + offset++) = wrenches_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < wrenches_length; i++){
+      offset += this->wrenches[i].serialize(outbuffer + offset);
+      }
+      offset += this->total_wrench.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = contact_positions_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < contact_positions_length; i++){
+      offset += this->contact_positions[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = contact_normals_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < contact_normals_length; i++){
+      offset += this->contact_normals[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = depths_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < depths_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_depthsi;
+      u_depthsi.real = this->depths[i];
+      *(outbuffer + offset + 0) = (u_depthsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_depthsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_depthsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_depthsi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_depthsi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_depthsi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_depthsi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_depthsi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->depths[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_info;
+      memcpy(&length_info, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_info; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_info-1]=0;
+      this->info = (char *)(inbuffer + offset-1);
+      offset += length_info;
+      uint32_t length_collision1_name;
+      memcpy(&length_collision1_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_collision1_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_collision1_name-1]=0;
+      this->collision1_name = (char *)(inbuffer + offset-1);
+      offset += length_collision1_name;
+      uint32_t length_collision2_name;
+      memcpy(&length_collision2_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_collision2_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_collision2_name-1]=0;
+      this->collision2_name = (char *)(inbuffer + offset-1);
+      offset += length_collision2_name;
+      uint8_t wrenches_lengthT = *(inbuffer + offset++);
+      if(wrenches_lengthT > wrenches_length)
+        this->wrenches = (geometry_msgs::Wrench*)realloc(this->wrenches, wrenches_lengthT * sizeof(geometry_msgs::Wrench));
+      offset += 3;
+      wrenches_length = wrenches_lengthT;
+      for( uint8_t i = 0; i < wrenches_length; i++){
+      offset += this->st_wrenches.deserialize(inbuffer + offset);
+        memcpy( &(this->wrenches[i]), &(this->st_wrenches), sizeof(geometry_msgs::Wrench));
+      }
+      offset += this->total_wrench.deserialize(inbuffer + offset);
+      uint8_t contact_positions_lengthT = *(inbuffer + offset++);
+      if(contact_positions_lengthT > contact_positions_length)
+        this->contact_positions = (geometry_msgs::Vector3*)realloc(this->contact_positions, contact_positions_lengthT * sizeof(geometry_msgs::Vector3));
+      offset += 3;
+      contact_positions_length = contact_positions_lengthT;
+      for( uint8_t i = 0; i < contact_positions_length; i++){
+      offset += this->st_contact_positions.deserialize(inbuffer + offset);
+        memcpy( &(this->contact_positions[i]), &(this->st_contact_positions), sizeof(geometry_msgs::Vector3));
+      }
+      uint8_t contact_normals_lengthT = *(inbuffer + offset++);
+      if(contact_normals_lengthT > contact_normals_length)
+        this->contact_normals = (geometry_msgs::Vector3*)realloc(this->contact_normals, contact_normals_lengthT * sizeof(geometry_msgs::Vector3));
+      offset += 3;
+      contact_normals_length = contact_normals_lengthT;
+      for( uint8_t i = 0; i < contact_normals_length; i++){
+      offset += this->st_contact_normals.deserialize(inbuffer + offset);
+        memcpy( &(this->contact_normals[i]), &(this->st_contact_normals), sizeof(geometry_msgs::Vector3));
+      }
+      uint8_t depths_lengthT = *(inbuffer + offset++);
+      if(depths_lengthT > depths_length)
+        this->depths = (double*)realloc(this->depths, depths_lengthT * sizeof(double));
+      offset += 3;
+      depths_length = depths_lengthT;
+      for( uint8_t i = 0; i < depths_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_depths;
+      u_st_depths.base = 0;
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_depths = u_st_depths.real;
+      offset += sizeof(this->st_depths);
+        memcpy( &(this->depths[i]), &(this->st_depths), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ContactState"; };
+    const char * getMD5(){ return "48c0ffb054b8c444f870cecea1ee50d9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ContactsState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ContactsState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_gazebo_msgs_ContactsState_h
+#define _ROS_gazebo_msgs_ContactsState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "gazebo_msgs/ContactState.h"
+
+namespace gazebo_msgs
+{
+
+  class ContactsState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t states_length;
+      gazebo_msgs::ContactState st_states;
+      gazebo_msgs::ContactState * states;
+
+    ContactsState():
+      header(),
+      states_length(0), states(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = states_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < states_length; i++){
+      offset += this->states[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t states_lengthT = *(inbuffer + offset++);
+      if(states_lengthT > states_length)
+        this->states = (gazebo_msgs::ContactState*)realloc(this->states, states_lengthT * sizeof(gazebo_msgs::ContactState));
+      offset += 3;
+      states_length = states_lengthT;
+      for( uint8_t i = 0; i < states_length; i++){
+      offset += this->st_states.deserialize(inbuffer + offset);
+        memcpy( &(this->states[i]), &(this->st_states), sizeof(gazebo_msgs::ContactState));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ContactsState"; };
+    const char * getMD5(){ return "acbcb1601a8e525bf72509f18e6f668d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/DeleteModel.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/DeleteModel.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,119 @@
+#ifndef _ROS_SERVICE_DeleteModel_h
+#define _ROS_SERVICE_DeleteModel_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char DELETEMODEL[] = "gazebo_msgs/DeleteModel";
+
+  class DeleteModelRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+
+    DeleteModelRequest():
+      model_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+     return offset;
+    }
+
+    const char * getType(){ return DELETEMODEL; };
+    const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; };
+
+  };
+
+  class DeleteModelResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    DeleteModelResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return DELETEMODEL; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class DeleteModel {
+    public:
+    typedef DeleteModelRequest Request;
+    typedef DeleteModelResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetJointProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetJointProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,272 @@
+#ifndef _ROS_SERVICE_GetJointProperties_h
+#define _ROS_SERVICE_GetJointProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETJOINTPROPERTIES[] = "gazebo_msgs/GetJointProperties";
+
+  class GetJointPropertiesRequest : public ros::Msg
+  {
+    public:
+      const char* joint_name;
+
+    GetJointPropertiesRequest():
+      joint_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_name, length_joint_name);
+      offset += length_joint_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_joint_name;
+      memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_joint_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_joint_name-1]=0;
+      this->joint_name = (char *)(inbuffer + offset-1);
+      offset += length_joint_name;
+     return offset;
+    }
+
+    const char * getType(){ return GETJOINTPROPERTIES; };
+    const char * getMD5(){ return "0be1351618e1dc030eb7959d9a4902de"; };
+
+  };
+
+  class GetJointPropertiesResponse : public ros::Msg
+  {
+    public:
+      uint8_t type;
+      uint8_t damping_length;
+      double st_damping;
+      double * damping;
+      uint8_t position_length;
+      double st_position;
+      double * position;
+      uint8_t rate_length;
+      double st_rate;
+      double * rate;
+      bool success;
+      const char* status_message;
+      enum { REVOLUTE =  0                 };
+      enum { CONTINUOUS =  1                 };
+      enum { PRISMATIC =  2                 };
+      enum { FIXED =  3                 };
+      enum { BALL =  4                 };
+      enum { UNIVERSAL =  5                 };
+
+    GetJointPropertiesResponse():
+      type(0),
+      damping_length(0), damping(NULL),
+      position_length(0), position(NULL),
+      rate_length(0), rate(NULL),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->type);
+      *(outbuffer + offset++) = damping_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < damping_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_dampingi;
+      u_dampingi.real = this->damping[i];
+      *(outbuffer + offset + 0) = (u_dampingi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_dampingi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_dampingi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_dampingi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_dampingi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_dampingi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_dampingi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_dampingi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->damping[i]);
+      }
+      *(outbuffer + offset++) = position_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_positioni;
+      u_positioni.real = this->position[i];
+      *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position[i]);
+      }
+      *(outbuffer + offset++) = rate_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < rate_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_ratei;
+      u_ratei.real = this->rate[i];
+      *(outbuffer + offset + 0) = (u_ratei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ratei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ratei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ratei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ratei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ratei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ratei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ratei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->rate[i]);
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->type);
+      uint8_t damping_lengthT = *(inbuffer + offset++);
+      if(damping_lengthT > damping_length)
+        this->damping = (double*)realloc(this->damping, damping_lengthT * sizeof(double));
+      offset += 3;
+      damping_length = damping_lengthT;
+      for( uint8_t i = 0; i < damping_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_damping;
+      u_st_damping.base = 0;
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_damping = u_st_damping.real;
+      offset += sizeof(this->st_damping);
+        memcpy( &(this->damping[i]), &(this->st_damping), sizeof(double));
+      }
+      uint8_t position_lengthT = *(inbuffer + offset++);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      offset += 3;
+      position_length = position_lengthT;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_position;
+      u_st_position.base = 0;
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_position = u_st_position.real;
+      offset += sizeof(this->st_position);
+        memcpy( &(this->position[i]), &(this->st_position), sizeof(double));
+      }
+      uint8_t rate_lengthT = *(inbuffer + offset++);
+      if(rate_lengthT > rate_length)
+        this->rate = (double*)realloc(this->rate, rate_lengthT * sizeof(double));
+      offset += 3;
+      rate_length = rate_lengthT;
+      for( uint8_t i = 0; i < rate_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_rate;
+      u_st_rate.base = 0;
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_rate.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_rate = u_st_rate.real;
+      offset += sizeof(this->st_rate);
+        memcpy( &(this->rate[i]), &(this->st_rate), sizeof(double));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETJOINTPROPERTIES; };
+    const char * getMD5(){ return "cd7b30a39faa372283dc94c5f6457f82"; };
+
+  };
+
+  class GetJointProperties {
+    public:
+    typedef GetJointPropertiesRequest Request;
+    typedef GetJointPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetLinkProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetLinkProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,358 @@
+#ifndef _ROS_SERVICE_GetLinkProperties_h
+#define _ROS_SERVICE_GetLinkProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETLINKPROPERTIES[] = "gazebo_msgs/GetLinkProperties";
+
+  class GetLinkPropertiesRequest : public ros::Msg
+  {
+    public:
+      const char* link_name;
+
+    GetLinkPropertiesRequest():
+      link_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_link_name = strlen(this->link_name);
+      memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->link_name, length_link_name);
+      offset += length_link_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_link_name;
+      memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_link_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_link_name-1]=0;
+      this->link_name = (char *)(inbuffer + offset-1);
+      offset += length_link_name;
+     return offset;
+    }
+
+    const char * getType(){ return GETLINKPROPERTIES; };
+    const char * getMD5(){ return "7d82d60381f1b66a30f2157f60884345"; };
+
+  };
+
+  class GetLinkPropertiesResponse : public ros::Msg
+  {
+    public:
+      geometry_msgs::Pose com;
+      bool gravity_mode;
+      double mass;
+      double ixx;
+      double ixy;
+      double ixz;
+      double iyy;
+      double iyz;
+      double izz;
+      bool success;
+      const char* status_message;
+
+    GetLinkPropertiesResponse():
+      com(),
+      gravity_mode(0),
+      mass(0),
+      ixx(0),
+      ixy(0),
+      ixz(0),
+      iyy(0),
+      iyz(0),
+      izz(0),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->com.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_gravity_mode;
+      u_gravity_mode.real = this->gravity_mode;
+      *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->gravity_mode);
+      union {
+        double real;
+        uint64_t base;
+      } u_mass;
+      u_mass.real = this->mass;
+      *(outbuffer + offset + 0) = (u_mass.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mass.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mass.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mass.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mass.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mass.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mass.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mass.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mass);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.real = this->ixx;
+      *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.real = this->ixy;
+      *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.real = this->ixz;
+      *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.real = this->iyy;
+      *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.real = this->iyz;
+      *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.real = this->izz;
+      *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->izz);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->com.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_gravity_mode;
+      u_gravity_mode.base = 0;
+      u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->gravity_mode = u_gravity_mode.real;
+      offset += sizeof(this->gravity_mode);
+      union {
+        double real;
+        uint64_t base;
+      } u_mass;
+      u_mass.base = 0;
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mass = u_mass.real;
+      offset += sizeof(this->mass);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.base = 0;
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixx = u_ixx.real;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.base = 0;
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixy = u_ixy.real;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.base = 0;
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixz = u_ixz.real;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.base = 0;
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyy = u_iyy.real;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.base = 0;
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyz = u_iyz.real;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.base = 0;
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->izz = u_izz.real;
+      offset += sizeof(this->izz);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETLINKPROPERTIES; };
+    const char * getMD5(){ return "a8619f92d17cfcc3958c0fd13299443d"; };
+
+  };
+
+  class GetLinkProperties {
+    public:
+    typedef GetLinkPropertiesRequest Request;
+    typedef GetLinkPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetLinkState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetLinkState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,140 @@
+#ifndef _ROS_SERVICE_GetLinkState_h
+#define _ROS_SERVICE_GetLinkState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "gazebo_msgs/LinkState.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETLINKSTATE[] = "gazebo_msgs/GetLinkState";
+
+  class GetLinkStateRequest : public ros::Msg
+  {
+    public:
+      const char* link_name;
+      const char* reference_frame;
+
+    GetLinkStateRequest():
+      link_name(""),
+      reference_frame("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_link_name = strlen(this->link_name);
+      memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->link_name, length_link_name);
+      offset += length_link_name;
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
+      offset += length_reference_frame;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_link_name;
+      memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_link_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_link_name-1]=0;
+      this->link_name = (char *)(inbuffer + offset-1);
+      offset += length_link_name;
+      uint32_t length_reference_frame;
+      memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_reference_frame-1]=0;
+      this->reference_frame = (char *)(inbuffer + offset-1);
+      offset += length_reference_frame;
+     return offset;
+    }
+
+    const char * getType(){ return GETLINKSTATE; };
+    const char * getMD5(){ return "7551675c30aaa71f7c288d4864552001"; };
+
+  };
+
+  class GetLinkStateResponse : public ros::Msg
+  {
+    public:
+      gazebo_msgs::LinkState link_state;
+      bool success;
+      const char* status_message;
+
+    GetLinkStateResponse():
+      link_state(),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->link_state.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->link_state.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETLINKSTATE; };
+    const char * getMD5(){ return "8ba55ad34f9c072e75c0de57b089753b"; };
+
+  };
+
+  class GetLinkState {
+    public:
+    typedef GetLinkStateRequest Request;
+    typedef GetLinkStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetModelProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetModelProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,296 @@
+#ifndef _ROS_SERVICE_GetModelProperties_h
+#define _ROS_SERVICE_GetModelProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETMODELPROPERTIES[] = "gazebo_msgs/GetModelProperties";
+
+  class GetModelPropertiesRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+
+    GetModelPropertiesRequest():
+      model_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+     return offset;
+    }
+
+    const char * getType(){ return GETMODELPROPERTIES; };
+    const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; };
+
+  };
+
+  class GetModelPropertiesResponse : public ros::Msg
+  {
+    public:
+      const char* parent_model_name;
+      const char* canonical_body_name;
+      uint8_t body_names_length;
+      char* st_body_names;
+      char* * body_names;
+      uint8_t geom_names_length;
+      char* st_geom_names;
+      char* * geom_names;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      uint8_t child_model_names_length;
+      char* st_child_model_names;
+      char* * child_model_names;
+      bool is_static;
+      bool success;
+      const char* status_message;
+
+    GetModelPropertiesResponse():
+      parent_model_name(""),
+      canonical_body_name(""),
+      body_names_length(0), body_names(NULL),
+      geom_names_length(0), geom_names(NULL),
+      joint_names_length(0), joint_names(NULL),
+      child_model_names_length(0), child_model_names(NULL),
+      is_static(0),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_parent_model_name = strlen(this->parent_model_name);
+      memcpy(outbuffer + offset, &length_parent_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->parent_model_name, length_parent_model_name);
+      offset += length_parent_model_name;
+      uint32_t length_canonical_body_name = strlen(this->canonical_body_name);
+      memcpy(outbuffer + offset, &length_canonical_body_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->canonical_body_name, length_canonical_body_name);
+      offset += length_canonical_body_name;
+      *(outbuffer + offset++) = body_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < body_names_length; i++){
+      uint32_t length_body_namesi = strlen(this->body_names[i]);
+      memcpy(outbuffer + offset, &length_body_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->body_names[i], length_body_namesi);
+      offset += length_body_namesi;
+      }
+      *(outbuffer + offset++) = geom_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < geom_names_length; i++){
+      uint32_t length_geom_namesi = strlen(this->geom_names[i]);
+      memcpy(outbuffer + offset, &length_geom_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->geom_names[i], length_geom_namesi);
+      offset += length_geom_namesi;
+      }
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset++) = child_model_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < child_model_names_length; i++){
+      uint32_t length_child_model_namesi = strlen(this->child_model_names[i]);
+      memcpy(outbuffer + offset, &length_child_model_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->child_model_names[i], length_child_model_namesi);
+      offset += length_child_model_namesi;
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_static;
+      u_is_static.real = this->is_static;
+      *(outbuffer + offset + 0) = (u_is_static.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_static);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_parent_model_name;
+      memcpy(&length_parent_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_parent_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_parent_model_name-1]=0;
+      this->parent_model_name = (char *)(inbuffer + offset-1);
+      offset += length_parent_model_name;
+      uint32_t length_canonical_body_name;
+      memcpy(&length_canonical_body_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_canonical_body_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_canonical_body_name-1]=0;
+      this->canonical_body_name = (char *)(inbuffer + offset-1);
+      offset += length_canonical_body_name;
+      uint8_t body_names_lengthT = *(inbuffer + offset++);
+      if(body_names_lengthT > body_names_length)
+        this->body_names = (char**)realloc(this->body_names, body_names_lengthT * sizeof(char*));
+      offset += 3;
+      body_names_length = body_names_lengthT;
+      for( uint8_t i = 0; i < body_names_length; i++){
+      uint32_t length_st_body_names;
+      memcpy(&length_st_body_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_body_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_body_names-1]=0;
+      this->st_body_names = (char *)(inbuffer + offset-1);
+      offset += length_st_body_names;
+        memcpy( &(this->body_names[i]), &(this->st_body_names), sizeof(char*));
+      }
+      uint8_t geom_names_lengthT = *(inbuffer + offset++);
+      if(geom_names_lengthT > geom_names_length)
+        this->geom_names = (char**)realloc(this->geom_names, geom_names_lengthT * sizeof(char*));
+      offset += 3;
+      geom_names_length = geom_names_lengthT;
+      for( uint8_t i = 0; i < geom_names_length; i++){
+      uint32_t length_st_geom_names;
+      memcpy(&length_st_geom_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_geom_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_geom_names-1]=0;
+      this->st_geom_names = (char *)(inbuffer + offset-1);
+      offset += length_st_geom_names;
+        memcpy( &(this->geom_names[i]), &(this->st_geom_names), sizeof(char*));
+      }
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      uint8_t child_model_names_lengthT = *(inbuffer + offset++);
+      if(child_model_names_lengthT > child_model_names_length)
+        this->child_model_names = (char**)realloc(this->child_model_names, child_model_names_lengthT * sizeof(char*));
+      offset += 3;
+      child_model_names_length = child_model_names_lengthT;
+      for( uint8_t i = 0; i < child_model_names_length; i++){
+      uint32_t length_st_child_model_names;
+      memcpy(&length_st_child_model_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_child_model_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_child_model_names-1]=0;
+      this->st_child_model_names = (char *)(inbuffer + offset-1);
+      offset += length_st_child_model_names;
+        memcpy( &(this->child_model_names[i]), &(this->st_child_model_names), sizeof(char*));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_static;
+      u_is_static.base = 0;
+      u_is_static.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_static = u_is_static.real;
+      offset += sizeof(this->is_static);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETMODELPROPERTIES; };
+    const char * getMD5(){ return "b7f370938ef77b464b95f1bab3ec5028"; };
+
+  };
+
+  class GetModelProperties {
+    public:
+    typedef GetModelPropertiesRequest Request;
+    typedef GetModelPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetModelState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetModelState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,145 @@
+#ifndef _ROS_SERVICE_GetModelState_h
+#define _ROS_SERVICE_GetModelState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState";
+
+  class GetModelStateRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+      const char* relative_entity_name;
+
+    GetModelStateRequest():
+      model_name(""),
+      relative_entity_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      uint32_t length_relative_entity_name = strlen(this->relative_entity_name);
+      memcpy(outbuffer + offset, &length_relative_entity_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name);
+      offset += length_relative_entity_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+      uint32_t length_relative_entity_name;
+      memcpy(&length_relative_entity_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_relative_entity_name-1]=0;
+      this->relative_entity_name = (char *)(inbuffer + offset-1);
+      offset += length_relative_entity_name;
+     return offset;
+    }
+
+    const char * getType(){ return GETMODELSTATE; };
+    const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; };
+
+  };
+
+  class GetModelStateResponse : public ros::Msg
+  {
+    public:
+      geometry_msgs::Pose pose;
+      geometry_msgs::Twist twist;
+      bool success;
+      const char* status_message;
+
+    GetModelStateResponse():
+      pose(),
+      twist(),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETMODELSTATE; };
+    const char * getMD5(){ return "1f8f991dc94e0cb27fe61383e0f576bb"; };
+
+  };
+
+  class GetModelState {
+    public:
+    typedef GetModelStateRequest Request;
+    typedef GetModelStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetPhysicsProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetPhysicsProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,192 @@
+#ifndef _ROS_SERVICE_GetPhysicsProperties_h
+#define _ROS_SERVICE_GetPhysicsProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+#include "gazebo_msgs/ODEPhysics.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETPHYSICSPROPERTIES[] = "gazebo_msgs/GetPhysicsProperties";
+
+  class GetPhysicsPropertiesRequest : public ros::Msg
+  {
+    public:
+
+    GetPhysicsPropertiesRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETPHYSICSPROPERTIES; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetPhysicsPropertiesResponse : public ros::Msg
+  {
+    public:
+      double time_step;
+      bool pause;
+      double max_update_rate;
+      geometry_msgs::Vector3 gravity;
+      gazebo_msgs::ODEPhysics ode_config;
+      bool success;
+      const char* status_message;
+
+    GetPhysicsPropertiesResponse():
+      time_step(0),
+      pause(0),
+      max_update_rate(0),
+      gravity(),
+      ode_config(),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.real = this->time_step;
+      *(outbuffer + offset + 0) = (u_time_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_time_step.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_time_step.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_time_step.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_time_step.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->time_step);
+      union {
+        bool real;
+        uint8_t base;
+      } u_pause;
+      u_pause.real = this->pause;
+      *(outbuffer + offset + 0) = (u_pause.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->pause);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_update_rate;
+      u_max_update_rate.real = this->max_update_rate;
+      *(outbuffer + offset + 0) = (u_max_update_rate.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_update_rate.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_update_rate.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_update_rate.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_update_rate.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_update_rate.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_update_rate.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_update_rate.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_update_rate);
+      offset += this->gravity.serialize(outbuffer + offset);
+      offset += this->ode_config.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.base = 0;
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->time_step = u_time_step.real;
+      offset += sizeof(this->time_step);
+      union {
+        bool real;
+        uint8_t base;
+      } u_pause;
+      u_pause.base = 0;
+      u_pause.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->pause = u_pause.real;
+      offset += sizeof(this->pause);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_update_rate;
+      u_max_update_rate.base = 0;
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_update_rate = u_max_update_rate.real;
+      offset += sizeof(this->max_update_rate);
+      offset += this->gravity.deserialize(inbuffer + offset);
+      offset += this->ode_config.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETPHYSICSPROPERTIES; };
+    const char * getMD5(){ return "575a5e74786981b7df2e3afc567693a6"; };
+
+  };
+
+  class GetPhysicsProperties {
+    public:
+    typedef GetPhysicsPropertiesRequest Request;
+    typedef GetPhysicsPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/GetWorldProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetWorldProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,183 @@
+#ifndef _ROS_SERVICE_GetWorldProperties_h
+#define _ROS_SERVICE_GetWorldProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETWORLDPROPERTIES[] = "gazebo_msgs/GetWorldProperties";
+
+  class GetWorldPropertiesRequest : public ros::Msg
+  {
+    public:
+
+    GetWorldPropertiesRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETWORLDPROPERTIES; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetWorldPropertiesResponse : public ros::Msg
+  {
+    public:
+      double sim_time;
+      uint8_t model_names_length;
+      char* st_model_names;
+      char* * model_names;
+      bool rendering_enabled;
+      bool success;
+      const char* status_message;
+
+    GetWorldPropertiesResponse():
+      sim_time(0),
+      model_names_length(0), model_names(NULL),
+      rendering_enabled(0),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_sim_time;
+      u_sim_time.real = this->sim_time;
+      *(outbuffer + offset + 0) = (u_sim_time.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sim_time.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sim_time.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sim_time.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sim_time.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sim_time.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sim_time.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sim_time.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sim_time);
+      *(outbuffer + offset++) = model_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < model_names_length; i++){
+      uint32_t length_model_namesi = strlen(this->model_names[i]);
+      memcpy(outbuffer + offset, &length_model_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_names[i], length_model_namesi);
+      offset += length_model_namesi;
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_rendering_enabled;
+      u_rendering_enabled.real = this->rendering_enabled;
+      *(outbuffer + offset + 0) = (u_rendering_enabled.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->rendering_enabled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_sim_time;
+      u_sim_time.base = 0;
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sim_time = u_sim_time.real;
+      offset += sizeof(this->sim_time);
+      uint8_t model_names_lengthT = *(inbuffer + offset++);
+      if(model_names_lengthT > model_names_length)
+        this->model_names = (char**)realloc(this->model_names, model_names_lengthT * sizeof(char*));
+      offset += 3;
+      model_names_length = model_names_lengthT;
+      for( uint8_t i = 0; i < model_names_length; i++){
+      uint32_t length_st_model_names;
+      memcpy(&length_st_model_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_model_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_model_names-1]=0;
+      this->st_model_names = (char *)(inbuffer + offset-1);
+      offset += length_st_model_names;
+        memcpy( &(this->model_names[i]), &(this->st_model_names), sizeof(char*));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_rendering_enabled;
+      u_rendering_enabled.base = 0;
+      u_rendering_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->rendering_enabled = u_rendering_enabled.real;
+      offset += sizeof(this->rendering_enabled);
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return GETWORLDPROPERTIES; };
+    const char * getMD5(){ return "36bb0f2eccf4d8be971410c22818ba3f"; };
+
+  };
+
+  class GetWorldProperties {
+    public:
+    typedef GetWorldPropertiesRequest Request;
+    typedef GetWorldPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/JointRequest.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/JointRequest.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_JointRequest_h
+#define _ROS_SERVICE_JointRequest_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char JOINTREQUEST[] = "gazebo_msgs/JointRequest";
+
+  class JointRequestRequest : public ros::Msg
+  {
+    public:
+      const char* joint_name;
+
+    JointRequestRequest():
+      joint_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_name, length_joint_name);
+      offset += length_joint_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_joint_name;
+      memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_joint_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_joint_name-1]=0;
+      this->joint_name = (char *)(inbuffer + offset-1);
+      offset += length_joint_name;
+     return offset;
+    }
+
+    const char * getType(){ return JOINTREQUEST; };
+    const char * getMD5(){ return "0be1351618e1dc030eb7959d9a4902de"; };
+
+  };
+
+  class JointRequestResponse : public ros::Msg
+  {
+    public:
+
+    JointRequestResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return JOINTREQUEST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class JointRequest {
+    public:
+    typedef JointRequestRequest Request;
+    typedef JointRequestResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/LinkState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/LinkState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,80 @@
+#ifndef _ROS_gazebo_msgs_LinkState_h
+#define _ROS_gazebo_msgs_LinkState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+  class LinkState : public ros::Msg
+  {
+    public:
+      const char* link_name;
+      geometry_msgs::Pose pose;
+      geometry_msgs::Twist twist;
+      const char* reference_frame;
+
+    LinkState():
+      link_name(""),
+      pose(),
+      twist(),
+      reference_frame("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_link_name = strlen(this->link_name);
+      memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->link_name, length_link_name);
+      offset += length_link_name;
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
+      offset += length_reference_frame;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_link_name;
+      memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_link_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_link_name-1]=0;
+      this->link_name = (char *)(inbuffer + offset-1);
+      offset += length_link_name;
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+      uint32_t length_reference_frame;
+      memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_reference_frame-1]=0;
+      this->reference_frame = (char *)(inbuffer + offset-1);
+      offset += length_reference_frame;
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/LinkState"; };
+    const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/LinkStates.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/LinkStates.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,112 @@
+#ifndef _ROS_gazebo_msgs_LinkStates_h
+#define _ROS_gazebo_msgs_LinkStates_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+  class LinkStates : public ros::Msg
+  {
+    public:
+      uint8_t name_length;
+      char* st_name;
+      char* * name;
+      uint8_t pose_length;
+      geometry_msgs::Pose st_pose;
+      geometry_msgs::Pose * pose;
+      uint8_t twist_length;
+      geometry_msgs::Twist st_twist;
+      geometry_msgs::Twist * twist;
+
+    LinkStates():
+      name_length(0), name(NULL),
+      pose_length(0), pose(NULL),
+      twist_length(0), twist(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset++) = pose_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = twist_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint8_t pose_lengthT = *(inbuffer + offset++);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      offset += 3;
+      pose_length = pose_lengthT;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->st_pose.deserialize(inbuffer + offset);
+        memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
+      }
+      uint8_t twist_lengthT = *(inbuffer + offset++);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      twist_length = twist_lengthT;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->st_twist.deserialize(inbuffer + offset);
+        memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/LinkStates"; };
+    const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ModelState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ModelState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,80 @@
+#ifndef _ROS_gazebo_msgs_ModelState_h
+#define _ROS_gazebo_msgs_ModelState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+  class ModelState : public ros::Msg
+  {
+    public:
+      const char* model_name;
+      geometry_msgs::Pose pose;
+      geometry_msgs::Twist twist;
+      const char* reference_frame;
+
+    ModelState():
+      model_name(""),
+      pose(),
+      twist(),
+      reference_frame("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
+      offset += length_reference_frame;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+      uint32_t length_reference_frame;
+      memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_reference_frame-1]=0;
+      this->reference_frame = (char *)(inbuffer + offset-1);
+      offset += length_reference_frame;
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ModelState"; };
+    const char * getMD5(){ return "9330fd35f2fcd82d457e54bd54e10593"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ModelStates.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ModelStates.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,112 @@
+#ifndef _ROS_gazebo_msgs_ModelStates_h
+#define _ROS_gazebo_msgs_ModelStates_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+
+namespace gazebo_msgs
+{
+
+  class ModelStates : public ros::Msg
+  {
+    public:
+      uint8_t name_length;
+      char* st_name;
+      char* * name;
+      uint8_t pose_length;
+      geometry_msgs::Pose st_pose;
+      geometry_msgs::Pose * pose;
+      uint8_t twist_length;
+      geometry_msgs::Twist st_twist;
+      geometry_msgs::Twist * twist;
+
+    ModelStates():
+      name_length(0), name(NULL),
+      pose_length(0), pose(NULL),
+      twist_length(0), twist(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset++) = pose_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = twist_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint8_t pose_lengthT = *(inbuffer + offset++);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      offset += 3;
+      pose_length = pose_lengthT;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->st_pose.deserialize(inbuffer + offset);
+        memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
+      }
+      uint8_t twist_lengthT = *(inbuffer + offset++);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      twist_length = twist_lengthT;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->st_twist.deserialize(inbuffer + offset);
+        memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ModelStates"; };
+    const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ODEJointProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ODEJointProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,508 @@
+#ifndef _ROS_gazebo_msgs_ODEJointProperties_h
+#define _ROS_gazebo_msgs_ODEJointProperties_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+  class ODEJointProperties : public ros::Msg
+  {
+    public:
+      uint8_t damping_length;
+      double st_damping;
+      double * damping;
+      uint8_t hiStop_length;
+      double st_hiStop;
+      double * hiStop;
+      uint8_t loStop_length;
+      double st_loStop;
+      double * loStop;
+      uint8_t erp_length;
+      double st_erp;
+      double * erp;
+      uint8_t cfm_length;
+      double st_cfm;
+      double * cfm;
+      uint8_t stop_erp_length;
+      double st_stop_erp;
+      double * stop_erp;
+      uint8_t stop_cfm_length;
+      double st_stop_cfm;
+      double * stop_cfm;
+      uint8_t fudge_factor_length;
+      double st_fudge_factor;
+      double * fudge_factor;
+      uint8_t fmax_length;
+      double st_fmax;
+      double * fmax;
+      uint8_t vel_length;
+      double st_vel;
+      double * vel;
+
+    ODEJointProperties():
+      damping_length(0), damping(NULL),
+      hiStop_length(0), hiStop(NULL),
+      loStop_length(0), loStop(NULL),
+      erp_length(0), erp(NULL),
+      cfm_length(0), cfm(NULL),
+      stop_erp_length(0), stop_erp(NULL),
+      stop_cfm_length(0), stop_cfm(NULL),
+      fudge_factor_length(0), fudge_factor(NULL),
+      fmax_length(0), fmax(NULL),
+      vel_length(0), vel(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = damping_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < damping_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_dampingi;
+      u_dampingi.real = this->damping[i];
+      *(outbuffer + offset + 0) = (u_dampingi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_dampingi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_dampingi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_dampingi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_dampingi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_dampingi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_dampingi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_dampingi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->damping[i]);
+      }
+      *(outbuffer + offset++) = hiStop_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < hiStop_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_hiStopi;
+      u_hiStopi.real = this->hiStop[i];
+      *(outbuffer + offset + 0) = (u_hiStopi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_hiStopi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_hiStopi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_hiStopi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_hiStopi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_hiStopi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_hiStopi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_hiStopi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->hiStop[i]);
+      }
+      *(outbuffer + offset++) = loStop_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < loStop_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_loStopi;
+      u_loStopi.real = this->loStop[i];
+      *(outbuffer + offset + 0) = (u_loStopi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_loStopi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_loStopi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_loStopi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_loStopi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_loStopi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_loStopi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_loStopi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->loStop[i]);
+      }
+      *(outbuffer + offset++) = erp_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < erp_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_erpi;
+      u_erpi.real = this->erp[i];
+      *(outbuffer + offset + 0) = (u_erpi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_erpi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_erpi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_erpi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_erpi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_erpi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_erpi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_erpi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->erp[i]);
+      }
+      *(outbuffer + offset++) = cfm_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < cfm_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_cfmi;
+      u_cfmi.real = this->cfm[i];
+      *(outbuffer + offset + 0) = (u_cfmi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cfmi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cfmi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cfmi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_cfmi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_cfmi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_cfmi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_cfmi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->cfm[i]);
+      }
+      *(outbuffer + offset++) = stop_erp_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < stop_erp_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_stop_erpi;
+      u_stop_erpi.real = this->stop_erp[i];
+      *(outbuffer + offset + 0) = (u_stop_erpi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_stop_erpi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_stop_erpi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_stop_erpi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_stop_erpi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_stop_erpi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_stop_erpi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_stop_erpi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->stop_erp[i]);
+      }
+      *(outbuffer + offset++) = stop_cfm_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < stop_cfm_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_stop_cfmi;
+      u_stop_cfmi.real = this->stop_cfm[i];
+      *(outbuffer + offset + 0) = (u_stop_cfmi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_stop_cfmi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_stop_cfmi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_stop_cfmi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_stop_cfmi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_stop_cfmi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_stop_cfmi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_stop_cfmi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->stop_cfm[i]);
+      }
+      *(outbuffer + offset++) = fudge_factor_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < fudge_factor_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_fudge_factori;
+      u_fudge_factori.real = this->fudge_factor[i];
+      *(outbuffer + offset + 0) = (u_fudge_factori.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_fudge_factori.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_fudge_factori.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_fudge_factori.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_fudge_factori.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_fudge_factori.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_fudge_factori.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_fudge_factori.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->fudge_factor[i]);
+      }
+      *(outbuffer + offset++) = fmax_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < fmax_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_fmaxi;
+      u_fmaxi.real = this->fmax[i];
+      *(outbuffer + offset + 0) = (u_fmaxi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_fmaxi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_fmaxi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_fmaxi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_fmaxi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_fmaxi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_fmaxi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_fmaxi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->fmax[i]);
+      }
+      *(outbuffer + offset++) = vel_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < vel_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_veli;
+      u_veli.real = this->vel[i];
+      *(outbuffer + offset + 0) = (u_veli.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_veli.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_veli.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_veli.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_veli.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_veli.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_veli.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_veli.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->vel[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t damping_lengthT = *(inbuffer + offset++);
+      if(damping_lengthT > damping_length)
+        this->damping = (double*)realloc(this->damping, damping_lengthT * sizeof(double));
+      offset += 3;
+      damping_length = damping_lengthT;
+      for( uint8_t i = 0; i < damping_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_damping;
+      u_st_damping.base = 0;
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_damping = u_st_damping.real;
+      offset += sizeof(this->st_damping);
+        memcpy( &(this->damping[i]), &(this->st_damping), sizeof(double));
+      }
+      uint8_t hiStop_lengthT = *(inbuffer + offset++);
+      if(hiStop_lengthT > hiStop_length)
+        this->hiStop = (double*)realloc(this->hiStop, hiStop_lengthT * sizeof(double));
+      offset += 3;
+      hiStop_length = hiStop_lengthT;
+      for( uint8_t i = 0; i < hiStop_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_hiStop;
+      u_st_hiStop.base = 0;
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_hiStop = u_st_hiStop.real;
+      offset += sizeof(this->st_hiStop);
+        memcpy( &(this->hiStop[i]), &(this->st_hiStop), sizeof(double));
+      }
+      uint8_t loStop_lengthT = *(inbuffer + offset++);
+      if(loStop_lengthT > loStop_length)
+        this->loStop = (double*)realloc(this->loStop, loStop_lengthT * sizeof(double));
+      offset += 3;
+      loStop_length = loStop_lengthT;
+      for( uint8_t i = 0; i < loStop_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_loStop;
+      u_st_loStop.base = 0;
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_loStop = u_st_loStop.real;
+      offset += sizeof(this->st_loStop);
+        memcpy( &(this->loStop[i]), &(this->st_loStop), sizeof(double));
+      }
+      uint8_t erp_lengthT = *(inbuffer + offset++);
+      if(erp_lengthT > erp_length)
+        this->erp = (double*)realloc(this->erp, erp_lengthT * sizeof(double));
+      offset += 3;
+      erp_length = erp_lengthT;
+      for( uint8_t i = 0; i < erp_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_erp;
+      u_st_erp.base = 0;
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_erp = u_st_erp.real;
+      offset += sizeof(this->st_erp);
+        memcpy( &(this->erp[i]), &(this->st_erp), sizeof(double));
+      }
+      uint8_t cfm_lengthT = *(inbuffer + offset++);
+      if(cfm_lengthT > cfm_length)
+        this->cfm = (double*)realloc(this->cfm, cfm_lengthT * sizeof(double));
+      offset += 3;
+      cfm_length = cfm_lengthT;
+      for( uint8_t i = 0; i < cfm_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_cfm;
+      u_st_cfm.base = 0;
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_cfm = u_st_cfm.real;
+      offset += sizeof(this->st_cfm);
+        memcpy( &(this->cfm[i]), &(this->st_cfm), sizeof(double));
+      }
+      uint8_t stop_erp_lengthT = *(inbuffer + offset++);
+      if(stop_erp_lengthT > stop_erp_length)
+        this->stop_erp = (double*)realloc(this->stop_erp, stop_erp_lengthT * sizeof(double));
+      offset += 3;
+      stop_erp_length = stop_erp_lengthT;
+      for( uint8_t i = 0; i < stop_erp_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_stop_erp;
+      u_st_stop_erp.base = 0;
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_stop_erp = u_st_stop_erp.real;
+      offset += sizeof(this->st_stop_erp);
+        memcpy( &(this->stop_erp[i]), &(this->st_stop_erp), sizeof(double));
+      }
+      uint8_t stop_cfm_lengthT = *(inbuffer + offset++);
+      if(stop_cfm_lengthT > stop_cfm_length)
+        this->stop_cfm = (double*)realloc(this->stop_cfm, stop_cfm_lengthT * sizeof(double));
+      offset += 3;
+      stop_cfm_length = stop_cfm_lengthT;
+      for( uint8_t i = 0; i < stop_cfm_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_stop_cfm;
+      u_st_stop_cfm.base = 0;
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_stop_cfm = u_st_stop_cfm.real;
+      offset += sizeof(this->st_stop_cfm);
+        memcpy( &(this->stop_cfm[i]), &(this->st_stop_cfm), sizeof(double));
+      }
+      uint8_t fudge_factor_lengthT = *(inbuffer + offset++);
+      if(fudge_factor_lengthT > fudge_factor_length)
+        this->fudge_factor = (double*)realloc(this->fudge_factor, fudge_factor_lengthT * sizeof(double));
+      offset += 3;
+      fudge_factor_length = fudge_factor_lengthT;
+      for( uint8_t i = 0; i < fudge_factor_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_fudge_factor;
+      u_st_fudge_factor.base = 0;
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_fudge_factor = u_st_fudge_factor.real;
+      offset += sizeof(this->st_fudge_factor);
+        memcpy( &(this->fudge_factor[i]), &(this->st_fudge_factor), sizeof(double));
+      }
+      uint8_t fmax_lengthT = *(inbuffer + offset++);
+      if(fmax_lengthT > fmax_length)
+        this->fmax = (double*)realloc(this->fmax, fmax_lengthT * sizeof(double));
+      offset += 3;
+      fmax_length = fmax_lengthT;
+      for( uint8_t i = 0; i < fmax_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_fmax;
+      u_st_fmax.base = 0;
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_fmax = u_st_fmax.real;
+      offset += sizeof(this->st_fmax);
+        memcpy( &(this->fmax[i]), &(this->st_fmax), sizeof(double));
+      }
+      uint8_t vel_lengthT = *(inbuffer + offset++);
+      if(vel_lengthT > vel_length)
+        this->vel = (double*)realloc(this->vel, vel_lengthT * sizeof(double));
+      offset += 3;
+      vel_length = vel_lengthT;
+      for( uint8_t i = 0; i < vel_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_vel;
+      u_st_vel.base = 0;
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_vel = u_st_vel.real;
+      offset += sizeof(this->st_vel);
+        memcpy( &(this->vel[i]), &(this->st_vel), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ODEJointProperties"; };
+    const char * getMD5(){ return "1b744c32a920af979f53afe2f9c3511f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/ODEPhysics.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ODEPhysics.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,277 @@
+#ifndef _ROS_gazebo_msgs_ODEPhysics_h
+#define _ROS_gazebo_msgs_ODEPhysics_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+  class ODEPhysics : public ros::Msg
+  {
+    public:
+      bool auto_disable_bodies;
+      uint32_t sor_pgs_precon_iters;
+      uint32_t sor_pgs_iters;
+      double sor_pgs_w;
+      double sor_pgs_rms_error_tol;
+      double contact_surface_layer;
+      double contact_max_correcting_vel;
+      double cfm;
+      double erp;
+      uint32_t max_contacts;
+
+    ODEPhysics():
+      auto_disable_bodies(0),
+      sor_pgs_precon_iters(0),
+      sor_pgs_iters(0),
+      sor_pgs_w(0),
+      sor_pgs_rms_error_tol(0),
+      contact_surface_layer(0),
+      contact_max_correcting_vel(0),
+      cfm(0),
+      erp(0),
+      max_contacts(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_auto_disable_bodies;
+      u_auto_disable_bodies.real = this->auto_disable_bodies;
+      *(outbuffer + offset + 0) = (u_auto_disable_bodies.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->auto_disable_bodies);
+      *(outbuffer + offset + 0) = (this->sor_pgs_precon_iters >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->sor_pgs_precon_iters >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->sor_pgs_precon_iters >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->sor_pgs_precon_iters >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sor_pgs_precon_iters);
+      *(outbuffer + offset + 0) = (this->sor_pgs_iters >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->sor_pgs_iters >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->sor_pgs_iters >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->sor_pgs_iters >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sor_pgs_iters);
+      union {
+        double real;
+        uint64_t base;
+      } u_sor_pgs_w;
+      u_sor_pgs_w.real = this->sor_pgs_w;
+      *(outbuffer + offset + 0) = (u_sor_pgs_w.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sor_pgs_w.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sor_pgs_w.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sor_pgs_w.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sor_pgs_w.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sor_pgs_w.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sor_pgs_w.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sor_pgs_w.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sor_pgs_w);
+      union {
+        double real;
+        uint64_t base;
+      } u_sor_pgs_rms_error_tol;
+      u_sor_pgs_rms_error_tol.real = this->sor_pgs_rms_error_tol;
+      *(outbuffer + offset + 0) = (u_sor_pgs_rms_error_tol.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sor_pgs_rms_error_tol.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sor_pgs_rms_error_tol.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sor_pgs_rms_error_tol.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sor_pgs_rms_error_tol.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sor_pgs_rms_error_tol.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sor_pgs_rms_error_tol.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sor_pgs_rms_error_tol.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sor_pgs_rms_error_tol);
+      union {
+        double real;
+        uint64_t base;
+      } u_contact_surface_layer;
+      u_contact_surface_layer.real = this->contact_surface_layer;
+      *(outbuffer + offset + 0) = (u_contact_surface_layer.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_contact_surface_layer.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_contact_surface_layer.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_contact_surface_layer.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_contact_surface_layer.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_contact_surface_layer.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_contact_surface_layer.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_contact_surface_layer.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->contact_surface_layer);
+      union {
+        double real;
+        uint64_t base;
+      } u_contact_max_correcting_vel;
+      u_contact_max_correcting_vel.real = this->contact_max_correcting_vel;
+      *(outbuffer + offset + 0) = (u_contact_max_correcting_vel.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_contact_max_correcting_vel.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_contact_max_correcting_vel.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_contact_max_correcting_vel.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_contact_max_correcting_vel.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_contact_max_correcting_vel.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_contact_max_correcting_vel.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_contact_max_correcting_vel.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->contact_max_correcting_vel);
+      union {
+        double real;
+        uint64_t base;
+      } u_cfm;
+      u_cfm.real = this->cfm;
+      *(outbuffer + offset + 0) = (u_cfm.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cfm.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cfm.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cfm.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_cfm.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_cfm.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_cfm.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_cfm.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->cfm);
+      union {
+        double real;
+        uint64_t base;
+      } u_erp;
+      u_erp.real = this->erp;
+      *(outbuffer + offset + 0) = (u_erp.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_erp.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_erp.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_erp.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_erp.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_erp.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_erp.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_erp.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->erp);
+      *(outbuffer + offset + 0) = (this->max_contacts >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->max_contacts >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->max_contacts >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->max_contacts >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->max_contacts);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_auto_disable_bodies;
+      u_auto_disable_bodies.base = 0;
+      u_auto_disable_bodies.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->auto_disable_bodies = u_auto_disable_bodies.real;
+      offset += sizeof(this->auto_disable_bodies);
+      this->sor_pgs_precon_iters =  ((uint32_t) (*(inbuffer + offset)));
+      this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->sor_pgs_precon_iters);
+      this->sor_pgs_iters =  ((uint32_t) (*(inbuffer + offset)));
+      this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->sor_pgs_iters);
+      union {
+        double real;
+        uint64_t base;
+      } u_sor_pgs_w;
+      u_sor_pgs_w.base = 0;
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sor_pgs_w.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sor_pgs_w = u_sor_pgs_w.real;
+      offset += sizeof(this->sor_pgs_w);
+      union {
+        double real;
+        uint64_t base;
+      } u_sor_pgs_rms_error_tol;
+      u_sor_pgs_rms_error_tol.base = 0;
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sor_pgs_rms_error_tol.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sor_pgs_rms_error_tol = u_sor_pgs_rms_error_tol.real;
+      offset += sizeof(this->sor_pgs_rms_error_tol);
+      union {
+        double real;
+        uint64_t base;
+      } u_contact_surface_layer;
+      u_contact_surface_layer.base = 0;
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_contact_surface_layer.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->contact_surface_layer = u_contact_surface_layer.real;
+      offset += sizeof(this->contact_surface_layer);
+      union {
+        double real;
+        uint64_t base;
+      } u_contact_max_correcting_vel;
+      u_contact_max_correcting_vel.base = 0;
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_contact_max_correcting_vel.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->contact_max_correcting_vel = u_contact_max_correcting_vel.real;
+      offset += sizeof(this->contact_max_correcting_vel);
+      union {
+        double real;
+        uint64_t base;
+      } u_cfm;
+      u_cfm.base = 0;
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_cfm.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->cfm = u_cfm.real;
+      offset += sizeof(this->cfm);
+      union {
+        double real;
+        uint64_t base;
+      } u_erp;
+      u_erp.base = 0;
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_erp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->erp = u_erp.real;
+      offset += sizeof(this->erp);
+      this->max_contacts =  ((uint32_t) (*(inbuffer + offset)));
+      this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->max_contacts);
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/ODEPhysics"; };
+    const char * getMD5(){ return "667d56ddbd547918c32d1934503dc335"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetJointProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetJointProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,124 @@
+#ifndef _ROS_SERVICE_SetJointProperties_h
+#define _ROS_SERVICE_SetJointProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "gazebo_msgs/ODEJointProperties.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETJOINTPROPERTIES[] = "gazebo_msgs/SetJointProperties";
+
+  class SetJointPropertiesRequest : public ros::Msg
+  {
+    public:
+      const char* joint_name;
+      gazebo_msgs::ODEJointProperties ode_joint_config;
+
+    SetJointPropertiesRequest():
+      joint_name(""),
+      ode_joint_config()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_name, length_joint_name);
+      offset += length_joint_name;
+      offset += this->ode_joint_config.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_joint_name;
+      memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_joint_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_joint_name-1]=0;
+      this->joint_name = (char *)(inbuffer + offset-1);
+      offset += length_joint_name;
+      offset += this->ode_joint_config.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETJOINTPROPERTIES; };
+    const char * getMD5(){ return "331fd8f35fd27e3c1421175590258e26"; };
+
+  };
+
+  class SetJointPropertiesResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetJointPropertiesResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETJOINTPROPERTIES; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetJointProperties {
+    public:
+    typedef SetJointPropertiesRequest Request;
+    typedef SetJointPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetJointTrajectory.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetJointTrajectory.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,163 @@
+#ifndef _ROS_SERVICE_SetJointTrajectory_h
+#define _ROS_SERVICE_SetJointTrajectory_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "trajectory_msgs/JointTrajectory.h"
+#include "geometry_msgs/Pose.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETJOINTTRAJECTORY[] = "gazebo_msgs/SetJointTrajectory";
+
+  class SetJointTrajectoryRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+      trajectory_msgs::JointTrajectory joint_trajectory;
+      geometry_msgs::Pose model_pose;
+      bool set_model_pose;
+      bool disable_physics_updates;
+
+    SetJointTrajectoryRequest():
+      model_name(""),
+      joint_trajectory(),
+      model_pose(),
+      set_model_pose(0),
+      disable_physics_updates(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      offset += this->joint_trajectory.serialize(outbuffer + offset);
+      offset += this->model_pose.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_set_model_pose;
+      u_set_model_pose.real = this->set_model_pose;
+      *(outbuffer + offset + 0) = (u_set_model_pose.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->set_model_pose);
+      union {
+        bool real;
+        uint8_t base;
+      } u_disable_physics_updates;
+      u_disable_physics_updates.real = this->disable_physics_updates;
+      *(outbuffer + offset + 0) = (u_disable_physics_updates.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->disable_physics_updates);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+      offset += this->joint_trajectory.deserialize(inbuffer + offset);
+      offset += this->model_pose.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_set_model_pose;
+      u_set_model_pose.base = 0;
+      u_set_model_pose.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->set_model_pose = u_set_model_pose.real;
+      offset += sizeof(this->set_model_pose);
+      union {
+        bool real;
+        uint8_t base;
+      } u_disable_physics_updates;
+      u_disable_physics_updates.base = 0;
+      u_disable_physics_updates.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->disable_physics_updates = u_disable_physics_updates.real;
+      offset += sizeof(this->disable_physics_updates);
+     return offset;
+    }
+
+    const char * getType(){ return SETJOINTTRAJECTORY; };
+    const char * getMD5(){ return "649dd2eba5ffd358069238825f9f85ab"; };
+
+  };
+
+  class SetJointTrajectoryResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetJointTrajectoryResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETJOINTTRAJECTORY; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetJointTrajectory {
+    public:
+    typedef SetJointTrajectoryRequest Request;
+    typedef SetJointTrajectoryResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetLinkProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetLinkProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,358 @@
+#ifndef _ROS_SERVICE_SetLinkProperties_h
+#define _ROS_SERVICE_SetLinkProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETLINKPROPERTIES[] = "gazebo_msgs/SetLinkProperties";
+
+  class SetLinkPropertiesRequest : public ros::Msg
+  {
+    public:
+      const char* link_name;
+      geometry_msgs::Pose com;
+      bool gravity_mode;
+      double mass;
+      double ixx;
+      double ixy;
+      double ixz;
+      double iyy;
+      double iyz;
+      double izz;
+
+    SetLinkPropertiesRequest():
+      link_name(""),
+      com(),
+      gravity_mode(0),
+      mass(0),
+      ixx(0),
+      ixy(0),
+      ixz(0),
+      iyy(0),
+      iyz(0),
+      izz(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_link_name = strlen(this->link_name);
+      memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->link_name, length_link_name);
+      offset += length_link_name;
+      offset += this->com.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_gravity_mode;
+      u_gravity_mode.real = this->gravity_mode;
+      *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->gravity_mode);
+      union {
+        double real;
+        uint64_t base;
+      } u_mass;
+      u_mass.real = this->mass;
+      *(outbuffer + offset + 0) = (u_mass.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mass.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mass.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mass.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mass.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mass.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mass.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mass.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mass);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.real = this->ixx;
+      *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.real = this->ixy;
+      *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.real = this->ixz;
+      *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.real = this->iyy;
+      *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.real = this->iyz;
+      *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.real = this->izz;
+      *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->izz);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_link_name;
+      memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_link_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_link_name-1]=0;
+      this->link_name = (char *)(inbuffer + offset-1);
+      offset += length_link_name;
+      offset += this->com.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_gravity_mode;
+      u_gravity_mode.base = 0;
+      u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->gravity_mode = u_gravity_mode.real;
+      offset += sizeof(this->gravity_mode);
+      union {
+        double real;
+        uint64_t base;
+      } u_mass;
+      u_mass.base = 0;
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mass.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mass = u_mass.real;
+      offset += sizeof(this->mass);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.base = 0;
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixx = u_ixx.real;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.base = 0;
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixy = u_ixy.real;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.base = 0;
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixz = u_ixz.real;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.base = 0;
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyy = u_iyy.real;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.base = 0;
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyz = u_iyz.real;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.base = 0;
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->izz = u_izz.real;
+      offset += sizeof(this->izz);
+     return offset;
+    }
+
+    const char * getType(){ return SETLINKPROPERTIES; };
+    const char * getMD5(){ return "68ac74a4be01b165bc305b5ccdc45e91"; };
+
+  };
+
+  class SetLinkPropertiesResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetLinkPropertiesResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETLINKPROPERTIES; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetLinkProperties {
+    public:
+    typedef SetLinkPropertiesRequest Request;
+    typedef SetLinkPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetLinkState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetLinkState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,108 @@
+#ifndef _ROS_SERVICE_SetLinkState_h
+#define _ROS_SERVICE_SetLinkState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "gazebo_msgs/LinkState.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETLINKSTATE[] = "gazebo_msgs/SetLinkState";
+
+  class SetLinkStateRequest : public ros::Msg
+  {
+    public:
+      gazebo_msgs::LinkState link_state;
+
+    SetLinkStateRequest():
+      link_state()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->link_state.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->link_state.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETLINKSTATE; };
+    const char * getMD5(){ return "22a2c757d56911b6f27868159e9a872d"; };
+
+  };
+
+  class SetLinkStateResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetLinkStateResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETLINKSTATE; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetLinkState {
+    public:
+    typedef SetLinkStateRequest Request;
+    typedef SetLinkStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetModelConfiguration.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetModelConfiguration.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,214 @@
+#ifndef _ROS_SERVICE_SetModelConfiguration_h
+#define _ROS_SERVICE_SetModelConfiguration_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETMODELCONFIGURATION[] = "gazebo_msgs/SetModelConfiguration";
+
+  class SetModelConfigurationRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+      const char* urdf_param_name;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      uint8_t joint_positions_length;
+      double st_joint_positions;
+      double * joint_positions;
+
+    SetModelConfigurationRequest():
+      model_name(""),
+      urdf_param_name(""),
+      joint_names_length(0), joint_names(NULL),
+      joint_positions_length(0), joint_positions(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      uint32_t length_urdf_param_name = strlen(this->urdf_param_name);
+      memcpy(outbuffer + offset, &length_urdf_param_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->urdf_param_name, length_urdf_param_name);
+      offset += length_urdf_param_name;
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset++) = joint_positions_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_positions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_joint_positionsi;
+      u_joint_positionsi.real = this->joint_positions[i];
+      *(outbuffer + offset + 0) = (u_joint_positionsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_joint_positionsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_joint_positionsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_joint_positionsi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_joint_positionsi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_joint_positionsi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_joint_positionsi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_joint_positionsi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->joint_positions[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+      uint32_t length_urdf_param_name;
+      memcpy(&length_urdf_param_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_urdf_param_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_urdf_param_name-1]=0;
+      this->urdf_param_name = (char *)(inbuffer + offset-1);
+      offset += length_urdf_param_name;
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      uint8_t joint_positions_lengthT = *(inbuffer + offset++);
+      if(joint_positions_lengthT > joint_positions_length)
+        this->joint_positions = (double*)realloc(this->joint_positions, joint_positions_lengthT * sizeof(double));
+      offset += 3;
+      joint_positions_length = joint_positions_lengthT;
+      for( uint8_t i = 0; i < joint_positions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_joint_positions;
+      u_st_joint_positions.base = 0;
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_joint_positions = u_st_joint_positions.real;
+      offset += sizeof(this->st_joint_positions);
+        memcpy( &(this->joint_positions[i]), &(this->st_joint_positions), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return SETMODELCONFIGURATION; };
+    const char * getMD5(){ return "160eae60f51fabff255480c70afa289f"; };
+
+  };
+
+  class SetModelConfigurationResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetModelConfigurationResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETMODELCONFIGURATION; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetModelConfiguration {
+    public:
+    typedef SetModelConfigurationRequest Request;
+    typedef SetModelConfigurationResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetModelState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetModelState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,108 @@
+#ifndef _ROS_SERVICE_SetModelState_h
+#define _ROS_SERVICE_SetModelState_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "gazebo_msgs/ModelState.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETMODELSTATE[] = "gazebo_msgs/SetModelState";
+
+  class SetModelStateRequest : public ros::Msg
+  {
+    public:
+      gazebo_msgs::ModelState model_state;
+
+    SetModelStateRequest():
+      model_state()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->model_state.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->model_state.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETMODELSTATE; };
+    const char * getMD5(){ return "cb042b0e91880f4661b29ea5b6234350"; };
+
+  };
+
+  class SetModelStateResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetModelStateResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETMODELSTATE; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetModelState {
+    public:
+    typedef SetModelStateRequest Request;
+    typedef SetModelStateResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SetPhysicsProperties.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetPhysicsProperties.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,175 @@
+#ifndef _ROS_SERVICE_SetPhysicsProperties_h
+#define _ROS_SERVICE_SetPhysicsProperties_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+#include "gazebo_msgs/ODEPhysics.h"
+
+namespace gazebo_msgs
+{
+
+static const char SETPHYSICSPROPERTIES[] = "gazebo_msgs/SetPhysicsProperties";
+
+  class SetPhysicsPropertiesRequest : public ros::Msg
+  {
+    public:
+      double time_step;
+      double max_update_rate;
+      geometry_msgs::Vector3 gravity;
+      gazebo_msgs::ODEPhysics ode_config;
+
+    SetPhysicsPropertiesRequest():
+      time_step(0),
+      max_update_rate(0),
+      gravity(),
+      ode_config()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.real = this->time_step;
+      *(outbuffer + offset + 0) = (u_time_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_time_step.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_time_step.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_time_step.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_time_step.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->time_step);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_update_rate;
+      u_max_update_rate.real = this->max_update_rate;
+      *(outbuffer + offset + 0) = (u_max_update_rate.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_update_rate.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_update_rate.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_update_rate.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_update_rate.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_update_rate.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_update_rate.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_update_rate.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_update_rate);
+      offset += this->gravity.serialize(outbuffer + offset);
+      offset += this->ode_config.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_time_step;
+      u_time_step.base = 0;
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->time_step = u_time_step.real;
+      offset += sizeof(this->time_step);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_update_rate;
+      u_max_update_rate.base = 0;
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_update_rate.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_update_rate = u_max_update_rate.real;
+      offset += sizeof(this->max_update_rate);
+      offset += this->gravity.deserialize(inbuffer + offset);
+      offset += this->ode_config.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETPHYSICSPROPERTIES; };
+    const char * getMD5(){ return "abd9f82732b52b92e9d6bb36e6a82452"; };
+
+  };
+
+  class SetPhysicsPropertiesResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetPhysicsPropertiesResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETPHYSICSPROPERTIES; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetPhysicsProperties {
+    public:
+    typedef SetPhysicsPropertiesRequest Request;
+    typedef SetPhysicsPropertiesResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/SpawnModel.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SpawnModel.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,172 @@
+#ifndef _ROS_SERVICE_SpawnModel_h
+#define _ROS_SERVICE_SpawnModel_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+
+namespace gazebo_msgs
+{
+
+static const char SPAWNMODEL[] = "gazebo_msgs/SpawnModel";
+
+  class SpawnModelRequest : public ros::Msg
+  {
+    public:
+      const char* model_name;
+      const char* model_xml;
+      const char* robot_namespace;
+      geometry_msgs::Pose initial_pose;
+      const char* reference_frame;
+
+    SpawnModelRequest():
+      model_name(""),
+      model_xml(""),
+      robot_namespace(""),
+      initial_pose(),
+      reference_frame("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      uint32_t length_model_xml = strlen(this->model_xml);
+      memcpy(outbuffer + offset, &length_model_xml, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_xml, length_model_xml);
+      offset += length_model_xml;
+      uint32_t length_robot_namespace = strlen(this->robot_namespace);
+      memcpy(outbuffer + offset, &length_robot_namespace, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->robot_namespace, length_robot_namespace);
+      offset += length_robot_namespace;
+      offset += this->initial_pose.serialize(outbuffer + offset);
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
+      offset += length_reference_frame;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_model_name;
+      memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_name-1]=0;
+      this->model_name = (char *)(inbuffer + offset-1);
+      offset += length_model_name;
+      uint32_t length_model_xml;
+      memcpy(&length_model_xml, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_model_xml; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_model_xml-1]=0;
+      this->model_xml = (char *)(inbuffer + offset-1);
+      offset += length_model_xml;
+      uint32_t length_robot_namespace;
+      memcpy(&length_robot_namespace, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_robot_namespace; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_robot_namespace-1]=0;
+      this->robot_namespace = (char *)(inbuffer + offset-1);
+      offset += length_robot_namespace;
+      offset += this->initial_pose.deserialize(inbuffer + offset);
+      uint32_t length_reference_frame;
+      memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_reference_frame-1]=0;
+      this->reference_frame = (char *)(inbuffer + offset-1);
+      offset += length_reference_frame;
+     return offset;
+    }
+
+    const char * getType(){ return SPAWNMODEL; };
+    const char * getMD5(){ return "6d0eba5753761cd57e6263a056b79930"; };
+
+  };
+
+  class SpawnModelResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SpawnModelResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SPAWNMODEL; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SpawnModel {
+    public:
+    typedef SpawnModelRequest Request;
+    typedef SpawnModelResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 gazebo_msgs/WorldState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/WorldState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,138 @@
+#ifndef _ROS_gazebo_msgs_WorldState_h
+#define _ROS_gazebo_msgs_WorldState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Twist.h"
+#include "geometry_msgs/Wrench.h"
+
+namespace gazebo_msgs
+{
+
+  class WorldState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t name_length;
+      char* st_name;
+      char* * name;
+      uint8_t pose_length;
+      geometry_msgs::Pose st_pose;
+      geometry_msgs::Pose * pose;
+      uint8_t twist_length;
+      geometry_msgs::Twist st_twist;
+      geometry_msgs::Twist * twist;
+      uint8_t wrench_length;
+      geometry_msgs::Wrench st_wrench;
+      geometry_msgs::Wrench * wrench;
+
+    WorldState():
+      header(),
+      name_length(0), name(NULL),
+      pose_length(0), pose(NULL),
+      twist_length(0), twist(NULL),
+      wrench_length(0), wrench(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset++) = pose_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = twist_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = wrench_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < wrench_length; i++){
+      offset += this->wrench[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint8_t pose_lengthT = *(inbuffer + offset++);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      offset += 3;
+      pose_length = pose_lengthT;
+      for( uint8_t i = 0; i < pose_length; i++){
+      offset += this->st_pose.deserialize(inbuffer + offset);
+        memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
+      }
+      uint8_t twist_lengthT = *(inbuffer + offset++);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      twist_length = twist_lengthT;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->st_twist.deserialize(inbuffer + offset);
+        memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
+      }
+      uint8_t wrench_lengthT = *(inbuffer + offset++);
+      if(wrench_lengthT > wrench_length)
+        this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
+      offset += 3;
+      wrench_length = wrench_lengthT;
+      for( uint8_t i = 0; i < wrench_length; i++){
+      offset += this->st_wrench.deserialize(inbuffer + offset);
+        memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "gazebo_msgs/WorldState"; };
+    const char * getMD5(){ return "de1a9de3ab7ba97ac0e9ec01a4eb481e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Accel.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Accel.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,47 @@
+#ifndef _ROS_geometry_msgs_Accel_h
+#define _ROS_geometry_msgs_Accel_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Accel : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 linear;
+      geometry_msgs::Vector3 angular;
+
+    Accel():
+      linear(),
+      angular()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->linear.serialize(outbuffer + offset);
+      offset += this->angular.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->linear.deserialize(inbuffer + offset);
+      offset += this->angular.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Accel"; };
+    const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/AccelStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_AccelStamped_h
+#define _ROS_geometry_msgs_AccelStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Accel.h"
+
+namespace geometry_msgs
+{
+
+  class AccelStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Accel accel;
+
+    AccelStamped():
+      header(),
+      accel()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->accel.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->accel.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/AccelStamped"; };
+    const char * getMD5(){ return "d8a98a5d81351b6eb0578c78557e7659"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/AccelWithCovariance.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelWithCovariance.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_geometry_msgs_AccelWithCovariance_h
+#define _ROS_geometry_msgs_AccelWithCovariance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Accel.h"
+
+namespace geometry_msgs
+{
+
+  class AccelWithCovariance : public ros::Msg
+  {
+    public:
+      geometry_msgs::Accel accel;
+      double covariance[36];
+
+    AccelWithCovariance():
+      accel(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->accel.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.real = this->covariance[i];
+      *(outbuffer + offset + 0) = (u_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->covariance[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->accel.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.base = 0;
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->covariance[i] = u_covariancei.real;
+      offset += sizeof(this->covariance[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/AccelWithCovariance"; };
+    const char * getMD5(){ return "ad5a718d699c6be72a02b8d6a139f334"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/AccelWithCovarianceStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelWithCovarianceStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_AccelWithCovarianceStamped_h
+#define _ROS_geometry_msgs_AccelWithCovarianceStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/AccelWithCovariance.h"
+
+namespace geometry_msgs
+{
+
+  class AccelWithCovarianceStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::AccelWithCovariance accel;
+
+    AccelWithCovarianceStamped():
+      header(),
+      accel()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->accel.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->accel.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/AccelWithCovarianceStamped"; };
+    const char * getMD5(){ return "96adb295225031ec8d57fb4251b0a886"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Inertia.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Inertia.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,260 @@
+#ifndef _ROS_geometry_msgs_Inertia_h
+#define _ROS_geometry_msgs_Inertia_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Inertia : public ros::Msg
+  {
+    public:
+      double m;
+      geometry_msgs::Vector3 com;
+      double ixx;
+      double ixy;
+      double ixz;
+      double iyy;
+      double iyz;
+      double izz;
+
+    Inertia():
+      m(0),
+      com(),
+      ixx(0),
+      ixy(0),
+      ixz(0),
+      iyy(0),
+      iyz(0),
+      izz(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_m;
+      u_m.real = this->m;
+      *(outbuffer + offset + 0) = (u_m.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m);
+      offset += this->com.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.real = this->ixx;
+      *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.real = this->ixy;
+      *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.real = this->ixz;
+      *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.real = this->iyy;
+      *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.real = this->iyz;
+      *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.real = this->izz;
+      *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->izz);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_m;
+      u_m.base = 0;
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m = u_m.real;
+      offset += sizeof(this->m);
+      offset += this->com.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixx;
+      u_ixx.base = 0;
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixx = u_ixx.real;
+      offset += sizeof(this->ixx);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixy;
+      u_ixy.base = 0;
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixy = u_ixy.real;
+      offset += sizeof(this->ixy);
+      union {
+        double real;
+        uint64_t base;
+      } u_ixz;
+      u_ixz.base = 0;
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->ixz = u_ixz.real;
+      offset += sizeof(this->ixz);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyy;
+      u_iyy.base = 0;
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyy = u_iyy.real;
+      offset += sizeof(this->iyy);
+      union {
+        double real;
+        uint64_t base;
+      } u_iyz;
+      u_iyz.base = 0;
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->iyz = u_iyz.real;
+      offset += sizeof(this->iyz);
+      union {
+        double real;
+        uint64_t base;
+      } u_izz;
+      u_izz.base = 0;
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->izz = u_izz.real;
+      offset += sizeof(this->izz);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Inertia"; };
+    const char * getMD5(){ return "1d26e4bb6c83ff141c5cf0d883c2b0fe"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/InertiaStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/InertiaStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_InertiaStamped_h
+#define _ROS_geometry_msgs_InertiaStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Inertia.h"
+
+namespace geometry_msgs
+{
+
+  class InertiaStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Inertia inertia;
+
+    InertiaStamped():
+      header(),
+      inertia()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->inertia.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->inertia.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/InertiaStamped"; };
+    const char * getMD5(){ return "ddee48caeab5a966c5e8d166654a9ac7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Point.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,131 @@
+#ifndef _ROS_geometry_msgs_Point_h
+#define _ROS_geometry_msgs_Point_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Point : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double z;
+
+    Point():
+      x(0),
+      y(0),
+      z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Point"; };
+    const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Point32.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point32.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,107 @@
+#ifndef _ROS_geometry_msgs_Point32_h
+#define _ROS_geometry_msgs_Point32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Point32 : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float z;
+
+    Point32():
+      x(0),
+      y(0),
+      z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Point32"; };
+    const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PointStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PointStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_PointStamped_h
+#define _ROS_geometry_msgs_PointStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point.h"
+
+namespace geometry_msgs
+{
+
+  class PointStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Point point;
+
+    PointStamped():
+      header(),
+      point()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->point.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->point.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PointStamped"; };
+    const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Polygon.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Polygon.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_geometry_msgs_Polygon_h
+#define _ROS_geometry_msgs_Polygon_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Point32.h"
+
+namespace geometry_msgs
+{
+
+  class Polygon : public ros::Msg
+  {
+    public:
+      uint8_t points_length;
+      geometry_msgs::Point32 st_points;
+      geometry_msgs::Point32 * points;
+
+    Polygon():
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Polygon"; };
+    const char * getMD5(){ return "cd60a26494a087f577976f0329fa120e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PolygonStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PolygonStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_PolygonStamped_h
+#define _ROS_geometry_msgs_PolygonStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Polygon.h"
+
+namespace geometry_msgs
+{
+
+  class PolygonStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Polygon polygon;
+
+    PolygonStamped():
+      header(),
+      polygon()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->polygon.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->polygon.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PolygonStamped"; };
+    const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Pose.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_Pose_h
+#define _ROS_geometry_msgs_Pose_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Point.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class Pose : public ros::Msg
+  {
+    public:
+      geometry_msgs::Point position;
+      geometry_msgs::Quaternion orientation;
+
+    Pose():
+      position(),
+      orientation()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->position.serialize(outbuffer + offset);
+      offset += this->orientation.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->position.deserialize(inbuffer + offset);
+      offset += this->orientation.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Pose"; };
+    const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Pose2D.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose2D.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,131 @@
+#ifndef _ROS_geometry_msgs_Pose2D_h
+#define _ROS_geometry_msgs_Pose2D_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Pose2D : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double theta;
+
+    Pose2D():
+      x(0),
+      y(0),
+      theta(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_theta;
+      u_theta.real = this->theta;
+      *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_theta.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_theta.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_theta.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_theta.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->theta);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_theta;
+      u_theta.base = 0;
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_theta.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->theta = u_theta.real;
+      offset += sizeof(this->theta);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Pose2D"; };
+    const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PoseArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_geometry_msgs_PoseArray_h
+#define _ROS_geometry_msgs_PoseArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseArray : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t poses_length;
+      geometry_msgs::Pose st_poses;
+      geometry_msgs::Pose * poses;
+
+    PoseArray():
+      header(),
+      poses_length(0), poses(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = poses_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t poses_lengthT = *(inbuffer + offset++);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose));
+      offset += 3;
+      poses_length = poses_lengthT;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->st_poses.deserialize(inbuffer + offset);
+        memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PoseArray"; };
+    const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PoseStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_PoseStamped_h
+#define _ROS_geometry_msgs_PoseStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Pose pose;
+
+    PoseStamped():
+      header(),
+      pose()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PoseStamped"; };
+    const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PoseWithCovariance.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovariance.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_geometry_msgs_PoseWithCovariance_h
+#define _ROS_geometry_msgs_PoseWithCovariance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseWithCovariance : public ros::Msg
+  {
+    public:
+      geometry_msgs::Pose pose;
+      double covariance[36];
+
+    PoseWithCovariance():
+      pose(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->pose.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.real = this->covariance[i];
+      *(outbuffer + offset + 0) = (u_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->covariance[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->pose.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.base = 0;
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->covariance[i] = u_covariancei.real;
+      offset += sizeof(this->covariance[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PoseWithCovariance"; };
+    const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/PoseWithCovarianceStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovarianceStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h
+#define _ROS_geometry_msgs_PoseWithCovarianceStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseWithCovariance.h"
+
+namespace geometry_msgs
+{
+
+  class PoseWithCovarianceStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::PoseWithCovariance pose;
+
+    PoseWithCovarianceStamped():
+      header(),
+      pose()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; };
+    const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Quaternion.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Quaternion.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,162 @@
+#ifndef _ROS_geometry_msgs_Quaternion_h
+#define _ROS_geometry_msgs_Quaternion_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Quaternion : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double z;
+      double w;
+
+    Quaternion():
+      x(0),
+      y(0),
+      z(0),
+      w(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->z);
+      union {
+        double real;
+        uint64_t base;
+      } u_w;
+      u_w.real = this->w;
+      *(outbuffer + offset + 0) = (u_w.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_w.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_w.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_w.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_w.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_w.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_w.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_w.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->w);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+      union {
+        double real;
+        uint64_t base;
+      } u_w;
+      u_w.base = 0;
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_w.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->w = u_w.real;
+      offset += sizeof(this->w);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Quaternion"; };
+    const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/QuaternionStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/QuaternionStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_QuaternionStamped_h
+#define _ROS_geometry_msgs_QuaternionStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class QuaternionStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Quaternion quaternion;
+
+    QuaternionStamped():
+      header(),
+      quaternion()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->quaternion.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->quaternion.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/QuaternionStamped"; };
+    const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Transform.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Transform.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_Transform_h
+#define _ROS_geometry_msgs_Transform_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class Transform : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 translation;
+      geometry_msgs::Quaternion rotation;
+
+    Transform():
+      translation(),
+      rotation()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->translation.serialize(outbuffer + offset);
+      offset += this->rotation.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->translation.deserialize(inbuffer + offset);
+      offset += this->rotation.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Transform"; };
+    const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/TransformStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TransformStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_geometry_msgs_TransformStamped_h
+#define _ROS_geometry_msgs_TransformStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Transform.h"
+
+namespace geometry_msgs
+{
+
+  class TransformStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* child_frame_id;
+      geometry_msgs::Transform transform;
+
+    TransformStamped():
+      header(),
+      child_frame_id(""),
+      transform()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_child_frame_id = strlen(this->child_frame_id);
+      memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
+      offset += length_child_frame_id;
+      offset += this->transform.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_child_frame_id;
+      memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_child_frame_id-1]=0;
+      this->child_frame_id = (char *)(inbuffer + offset-1);
+      offset += length_child_frame_id;
+      offset += this->transform.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/TransformStamped"; };
+    const char * getMD5(){ return "b5764a33bfeb3588febc2682852579b0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Twist.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Twist.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,47 @@
+#ifndef _ROS_geometry_msgs_Twist_h
+#define _ROS_geometry_msgs_Twist_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Twist : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 linear;
+      geometry_msgs::Vector3 angular;
+
+    Twist():
+      linear(),
+      angular()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->linear.serialize(outbuffer + offset);
+      offset += this->angular.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->linear.deserialize(inbuffer + offset);
+      offset += this->angular.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Twist"; };
+    const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/TwistStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_TwistStamped_h
+#define _ROS_geometry_msgs_TwistStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Twist.h"
+
+namespace geometry_msgs
+{
+
+  class TwistStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Twist twist;
+
+    TwistStamped():
+      header(),
+      twist()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/TwistStamped"; };
+    const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/TwistWithCovariance.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovariance.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_geometry_msgs_TwistWithCovariance_h
+#define _ROS_geometry_msgs_TwistWithCovariance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Twist.h"
+
+namespace geometry_msgs
+{
+
+  class TwistWithCovariance : public ros::Msg
+  {
+    public:
+      geometry_msgs::Twist twist;
+      double covariance[36];
+
+    TwistWithCovariance():
+      twist(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->twist.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.real = this->covariance[i];
+      *(outbuffer + offset + 0) = (u_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->covariance[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->twist.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 36; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_covariancei;
+      u_covariancei.base = 0;
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->covariance[i] = u_covariancei.real;
+      offset += sizeof(this->covariance[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/TwistWithCovariance"; };
+    const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/TwistWithCovarianceStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovarianceStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h
+#define _ROS_geometry_msgs_TwistWithCovarianceStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/TwistWithCovariance.h"
+
+namespace geometry_msgs
+{
+
+  class TwistWithCovarianceStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::TwistWithCovariance twist;
+
+    TwistWithCovarianceStamped():
+      header(),
+      twist()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; };
+    const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Vector3.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,131 @@
+#ifndef _ROS_geometry_msgs_Vector3_h
+#define _ROS_geometry_msgs_Vector3_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Vector3 : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double z;
+
+    Vector3():
+      x(0),
+      y(0),
+      z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Vector3"; };
+    const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Vector3Stamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3Stamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_Vector3Stamped_h
+#define _ROS_geometry_msgs_Vector3Stamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Vector3Stamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Vector3 vector;
+
+    Vector3Stamped():
+      header(),
+      vector()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->vector.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->vector.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Vector3Stamped"; };
+    const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/Wrench.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Wrench.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,47 @@
+#ifndef _ROS_geometry_msgs_Wrench_h
+#define _ROS_geometry_msgs_Wrench_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Wrench : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 force;
+      geometry_msgs::Vector3 torque;
+
+    Wrench():
+      force(),
+      torque()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->force.serialize(outbuffer + offset);
+      offset += this->torque.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->force.deserialize(inbuffer + offset);
+      offset += this->torque.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/Wrench"; };
+    const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 geometry_msgs/WrenchStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/WrenchStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_geometry_msgs_WrenchStamped_h
+#define _ROS_geometry_msgs_WrenchStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Wrench.h"
+
+namespace geometry_msgs
+{
+
+  class WrenchStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Wrench wrench;
+
+    WrenchStamped():
+      header(),
+      wrench()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->wrench.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->wrench.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "geometry_msgs/WrenchStamped"; };
+    const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 laser_assembler/AssembleScans.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/laser_assembler/AssembleScans.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,120 @@
+#ifndef _ROS_SERVICE_AssembleScans_h
+#define _ROS_SERVICE_AssembleScans_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+#include "sensor_msgs/PointCloud.h"
+
+namespace laser_assembler
+{
+
+static const char ASSEMBLESCANS[] = "laser_assembler/AssembleScans";
+
+  class AssembleScansRequest : public ros::Msg
+  {
+    public:
+      ros::Time begin;
+      ros::Time end;
+
+    AssembleScansRequest():
+      begin(),
+      end()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->begin.sec);
+      *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->begin.nsec);
+      *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->end.sec);
+      *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->end.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->begin.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->begin.sec);
+      this->begin.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->begin.nsec);
+      this->end.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->end.sec);
+      this->end.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->end.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return ASSEMBLESCANS; };
+    const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; };
+
+  };
+
+  class AssembleScansResponse : public ros::Msg
+  {
+    public:
+      sensor_msgs::PointCloud cloud;
+
+    AssembleScansResponse():
+      cloud()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->cloud.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->cloud.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return ASSEMBLESCANS; };
+    const char * getMD5(){ return "4217b28a903e4ad7869a83b3653110ff"; };
+
+  };
+
+  class AssembleScans {
+    public:
+    typedef AssembleScansRequest Request;
+    typedef AssembleScansResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 laser_assembler/AssembleScans2.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/laser_assembler/AssembleScans2.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,120 @@
+#ifndef _ROS_SERVICE_AssembleScans2_h
+#define _ROS_SERVICE_AssembleScans2_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/PointCloud2.h"
+#include "ros/time.h"
+
+namespace laser_assembler
+{
+
+static const char ASSEMBLESCANS2[] = "laser_assembler/AssembleScans2";
+
+  class AssembleScans2Request : public ros::Msg
+  {
+    public:
+      ros::Time begin;
+      ros::Time end;
+
+    AssembleScans2Request():
+      begin(),
+      end()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->begin.sec);
+      *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->begin.nsec);
+      *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->end.sec);
+      *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->end.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->begin.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->begin.sec);
+      this->begin.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->begin.nsec);
+      this->end.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->end.sec);
+      this->end.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->end.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return ASSEMBLESCANS2; };
+    const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; };
+
+  };
+
+  class AssembleScans2Response : public ros::Msg
+  {
+    public:
+      sensor_msgs::PointCloud2 cloud;
+
+    AssembleScans2Response():
+      cloud()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->cloud.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->cloud.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return ASSEMBLESCANS2; };
+    const char * getMD5(){ return "96cec5374164b3b3d1d7ef5d7628a7ed"; };
+
+  };
+
+  class AssembleScans2 {
+    public:
+    typedef AssembleScans2Request Request;
+    typedef AssembleScans2Response Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/GetMapROI.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetMapROI.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,199 @@
+#ifndef _ROS_SERVICE_GetMapROI_h
+#define _ROS_SERVICE_GetMapROI_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+
+namespace map_msgs
+{
+
+static const char GETMAPROI[] = "map_msgs/GetMapROI";
+
+  class GetMapROIRequest : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double l_x;
+      double l_y;
+
+    GetMapROIRequest():
+      x(0),
+      y(0),
+      l_x(0),
+      l_y(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_x;
+      u_l_x.real = this->l_x;
+      *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->l_x);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_y;
+      u_l_y.real = this->l_y;
+      *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->l_y);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_x;
+      u_l_x.base = 0;
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->l_x = u_l_x.real;
+      offset += sizeof(this->l_x);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_y;
+      u_l_y.base = 0;
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->l_y = u_l_y.real;
+      offset += sizeof(this->l_y);
+     return offset;
+    }
+
+    const char * getType(){ return GETMAPROI; };
+    const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; };
+
+  };
+
+  class GetMapROIResponse : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid sub_map;
+
+    GetMapROIResponse():
+      sub_map()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->sub_map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->sub_map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETMAPROI; };
+    const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; };
+
+  };
+
+  class GetMapROI {
+    public:
+    typedef GetMapROIRequest Request;
+    typedef GetMapROIResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/GetPointMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetPointMap.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,75 @@
+#ifndef _ROS_SERVICE_GetPointMap_h
+#define _ROS_SERVICE_GetPointMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/PointCloud2.h"
+
+namespace map_msgs
+{
+
+static const char GETPOINTMAP[] = "map_msgs/GetPointMap";
+
+  class GetPointMapRequest : public ros::Msg
+  {
+    public:
+
+    GetPointMapRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETPOINTMAP; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetPointMapResponse : public ros::Msg
+  {
+    public:
+      sensor_msgs::PointCloud2 map;
+
+    GetPointMapResponse():
+      map()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETPOINTMAP; };
+    const char * getMD5(){ return "b84fbb39505086eb6a62d933c75cb7b4"; };
+
+  };
+
+  class GetPointMap {
+    public:
+    typedef GetPointMapRequest Request;
+    typedef GetPointMapResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/GetPointMapROI.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetPointMapROI.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,292 @@
+#ifndef _ROS_SERVICE_GetPointMapROI_h
+#define _ROS_SERVICE_GetPointMapROI_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/PointCloud2.h"
+
+namespace map_msgs
+{
+
+static const char GETPOINTMAPROI[] = "map_msgs/GetPointMapROI";
+
+  class GetPointMapROIRequest : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double z;
+      double r;
+      double l_x;
+      double l_y;
+      double l_z;
+
+    GetPointMapROIRequest():
+      x(0),
+      y(0),
+      z(0),
+      r(0),
+      l_x(0),
+      l_y(0),
+      l_z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->z);
+      union {
+        double real;
+        uint64_t base;
+      } u_r;
+      u_r.real = this->r;
+      *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_r.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_r.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_r.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_r.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->r);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_x;
+      u_l_x.real = this->l_x;
+      *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->l_x);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_y;
+      u_l_y.real = this->l_y;
+      *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->l_y);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_z;
+      u_l_z.real = this->l_z;
+      *(outbuffer + offset + 0) = (u_l_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_l_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_l_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_l_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_l_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_l_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_l_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_l_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->l_z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+      union {
+        double real;
+        uint64_t base;
+      } u_r;
+      u_r.base = 0;
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_r.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->r = u_r.real;
+      offset += sizeof(this->r);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_x;
+      u_l_x.base = 0;
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->l_x = u_l_x.real;
+      offset += sizeof(this->l_x);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_y;
+      u_l_y.base = 0;
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->l_y = u_l_y.real;
+      offset += sizeof(this->l_y);
+      union {
+        double real;
+        uint64_t base;
+      } u_l_z;
+      u_l_z.base = 0;
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->l_z = u_l_z.real;
+      offset += sizeof(this->l_z);
+     return offset;
+    }
+
+    const char * getType(){ return GETPOINTMAPROI; };
+    const char * getMD5(){ return "895f7e437a9a6dd225316872b187a303"; };
+
+  };
+
+  class GetPointMapROIResponse : public ros::Msg
+  {
+    public:
+      sensor_msgs::PointCloud2 sub_map;
+
+    GetPointMapROIResponse():
+      sub_map()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->sub_map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->sub_map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETPOINTMAPROI; };
+    const char * getMD5(){ return "313769f8b0e724525c6463336cbccd63"; };
+
+  };
+
+  class GetPointMapROI {
+    public:
+    typedef GetPointMapROIRequest Request;
+    typedef GetPointMapROIResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/OccupancyGridUpdate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/OccupancyGridUpdate.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,146 @@
+#ifndef _ROS_map_msgs_OccupancyGridUpdate_h
+#define _ROS_map_msgs_OccupancyGridUpdate_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace map_msgs
+{
+
+  class OccupancyGridUpdate : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      int32_t x;
+      int32_t y;
+      uint32_t width;
+      uint32_t height;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
+
+    OccupancyGridUpdate():
+      header(),
+      x(0),
+      y(0),
+      width(0),
+      height(0),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "map_msgs/OccupancyGridUpdate"; };
+    const char * getMD5(){ return "b295be292b335c34718bd939deebe1c9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 map_msgs/PointCloud2Update.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/PointCloud2Update.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,62 @@
+#ifndef _ROS_map_msgs_PointCloud2Update_h
+#define _ROS_map_msgs_PointCloud2Update_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/PointCloud2.h"
+
+namespace map_msgs
+{
+
+  class PointCloud2Update : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint32_t type;
+      sensor_msgs::PointCloud2 points;
+      enum { ADD = 0 };
+      enum { DELETE = 1 };
+
+    PointCloud2Update():
+      header(),
+      type(0),
+      points()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->type >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->type >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->type >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->type);
+      offset += this->points.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->type =  ((uint32_t) (*(inbuffer + offset)));
+      this->type |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->type |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->type |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->type);
+      offset += this->points.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "map_msgs/PointCloud2Update"; };
+    const char * getMD5(){ return "6c58e4f249ae9cd2b24fb1ee0f99195e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 map_msgs/ProjectedMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMap.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,105 @@
+#ifndef _ROS_map_msgs_ProjectedMap_h
+#define _ROS_map_msgs_ProjectedMap_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+
+namespace map_msgs
+{
+
+  class ProjectedMap : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid map;
+      double min_z;
+      double max_z;
+
+    ProjectedMap():
+      map(),
+      min_z(0),
+      max_z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_min_z;
+      u_min_z.real = this->min_z;
+      *(outbuffer + offset + 0) = (u_min_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_min_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_min_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_min_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_min_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_min_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_min_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_min_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->min_z);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_z;
+      u_max_z.real = this->max_z;
+      *(outbuffer + offset + 0) = (u_max_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_min_z;
+      u_min_z.base = 0;
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->min_z = u_min_z.real;
+      offset += sizeof(this->min_z);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_z;
+      u_max_z.base = 0;
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_z = u_max_z.real;
+      offset += sizeof(this->max_z);
+     return offset;
+    }
+
+    const char * getType(){ return "map_msgs/ProjectedMap"; };
+    const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 map_msgs/ProjectedMapInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMapInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,240 @@
+#ifndef _ROS_map_msgs_ProjectedMapInfo_h
+#define _ROS_map_msgs_ProjectedMapInfo_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace map_msgs
+{
+
+  class ProjectedMapInfo : public ros::Msg
+  {
+    public:
+      const char* frame_id;
+      double x;
+      double y;
+      double width;
+      double height;
+      double min_z;
+      double max_z;
+
+    ProjectedMapInfo():
+      frame_id(""),
+      x(0),
+      y(0),
+      width(0),
+      height(0),
+      min_z(0),
+      max_z(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_frame_id = strlen(this->frame_id);
+      memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->frame_id, length_frame_id);
+      offset += length_frame_id;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_width.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_width.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_width.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_width.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_height.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_height.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_height.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_height.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->height);
+      union {
+        double real;
+        uint64_t base;
+      } u_min_z;
+      u_min_z.real = this->min_z;
+      *(outbuffer + offset + 0) = (u_min_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_min_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_min_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_min_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_min_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_min_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_min_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_min_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->min_z);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_z;
+      u_max_z.real = this->max_z;
+      *(outbuffer + offset + 0) = (u_max_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_z.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_max_z.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_max_z.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_max_z.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_max_z.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->max_z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_frame_id;
+      memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_frame_id-1]=0;
+      this->frame_id = (char *)(inbuffer + offset-1);
+      offset += length_frame_id;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      union {
+        double real;
+        uint64_t base;
+      } u_min_z;
+      u_min_z.base = 0;
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->min_z = u_min_z.real;
+      offset += sizeof(this->min_z);
+      union {
+        double real;
+        uint64_t base;
+      } u_max_z;
+      u_max_z.base = 0;
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->max_z = u_max_z.real;
+      offset += sizeof(this->max_z);
+     return offset;
+    }
+
+    const char * getType(){ return "map_msgs/ProjectedMapInfo"; };
+    const char * getMD5(){ return "2dc10595ae94de23f22f8a6d2a0eef7a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 map_msgs/ProjectedMapsInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMapsInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,91 @@
+#ifndef _ROS_SERVICE_ProjectedMapsInfo_h
+#define _ROS_SERVICE_ProjectedMapsInfo_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "map_msgs/ProjectedMapInfo.h"
+
+namespace map_msgs
+{
+
+static const char PROJECTEDMAPSINFO[] = "map_msgs/ProjectedMapsInfo";
+
+  class ProjectedMapsInfoRequest : public ros::Msg
+  {
+    public:
+      uint8_t projected_maps_info_length;
+      map_msgs::ProjectedMapInfo st_projected_maps_info;
+      map_msgs::ProjectedMapInfo * projected_maps_info;
+
+    ProjectedMapsInfoRequest():
+      projected_maps_info_length(0), projected_maps_info(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = projected_maps_info_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < projected_maps_info_length; i++){
+      offset += this->projected_maps_info[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t projected_maps_info_lengthT = *(inbuffer + offset++);
+      if(projected_maps_info_lengthT > projected_maps_info_length)
+        this->projected_maps_info = (map_msgs::ProjectedMapInfo*)realloc(this->projected_maps_info, projected_maps_info_lengthT * sizeof(map_msgs::ProjectedMapInfo));
+      offset += 3;
+      projected_maps_info_length = projected_maps_info_lengthT;
+      for( uint8_t i = 0; i < projected_maps_info_length; i++){
+      offset += this->st_projected_maps_info.deserialize(inbuffer + offset);
+        memcpy( &(this->projected_maps_info[i]), &(this->st_projected_maps_info), sizeof(map_msgs::ProjectedMapInfo));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return PROJECTEDMAPSINFO; };
+    const char * getMD5(){ return "d7980a33202421c8cd74565e57a4d229"; };
+
+  };
+
+  class ProjectedMapsInfoResponse : public ros::Msg
+  {
+    public:
+
+    ProjectedMapsInfoResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return PROJECTEDMAPSINFO; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class ProjectedMapsInfo {
+    public:
+    typedef ProjectedMapsInfoRequest Request;
+    typedef ProjectedMapsInfoResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/SaveMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/SaveMap.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,75 @@
+#ifndef _ROS_SERVICE_SaveMap_h
+#define _ROS_SERVICE_SaveMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/String.h"
+
+namespace map_msgs
+{
+
+static const char SAVEMAP[] = "map_msgs/SaveMap";
+
+  class SaveMapRequest : public ros::Msg
+  {
+    public:
+      std_msgs::String filename;
+
+    SaveMapRequest():
+      filename()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->filename.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->filename.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SAVEMAP; };
+    const char * getMD5(){ return "716e25f9d9dc76ceba197f93cbf05dc7"; };
+
+  };
+
+  class SaveMapResponse : public ros::Msg
+  {
+    public:
+
+    SaveMapResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SAVEMAP; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SaveMap {
+    public:
+    typedef SaveMapRequest Request;
+    typedef SaveMapResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 map_msgs/SetMapProjections.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/SetMapProjections.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,91 @@
+#ifndef _ROS_SERVICE_SetMapProjections_h
+#define _ROS_SERVICE_SetMapProjections_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "map_msgs/ProjectedMapInfo.h"
+
+namespace map_msgs
+{
+
+static const char SETMAPPROJECTIONS[] = "map_msgs/SetMapProjections";
+
+  class SetMapProjectionsRequest : public ros::Msg
+  {
+    public:
+
+    SetMapProjectionsRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SETMAPPROJECTIONS; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SetMapProjectionsResponse : public ros::Msg
+  {
+    public:
+      uint8_t projected_maps_info_length;
+      map_msgs::ProjectedMapInfo st_projected_maps_info;
+      map_msgs::ProjectedMapInfo * projected_maps_info;
+
+    SetMapProjectionsResponse():
+      projected_maps_info_length(0), projected_maps_info(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = projected_maps_info_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < projected_maps_info_length; i++){
+      offset += this->projected_maps_info[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t projected_maps_info_lengthT = *(inbuffer + offset++);
+      if(projected_maps_info_lengthT > projected_maps_info_length)
+        this->projected_maps_info = (map_msgs::ProjectedMapInfo*)realloc(this->projected_maps_info, projected_maps_info_lengthT * sizeof(map_msgs::ProjectedMapInfo));
+      offset += 3;
+      projected_maps_info_length = projected_maps_info_lengthT;
+      for( uint8_t i = 0; i < projected_maps_info_length; i++){
+      offset += this->st_projected_maps_info.deserialize(inbuffer + offset);
+        memcpy( &(this->projected_maps_info[i]), &(this->st_projected_maps_info), sizeof(map_msgs::ProjectedMapInfo));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return SETMAPPROJECTIONS; };
+    const char * getMD5(){ return "d7980a33202421c8cd74565e57a4d229"; };
+
+  };
+
+  class SetMapProjections {
+    public:
+    typedef SetMapProjectionsRequest Request;
+    typedef SetMapProjectionsResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMap.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,75 @@
+#ifndef _ROS_SERVICE_GetMap_h
+#define _ROS_SERVICE_GetMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+
+namespace nav_msgs
+{
+
+static const char GETMAP[] = "nav_msgs/GetMap";
+
+  class GetMapRequest : public ros::Msg
+  {
+    public:
+
+    GetMapRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETMAP; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetMapResponse : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid map;
+
+    GetMapResponse():
+      map()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETMAP; };
+    const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; };
+
+  };
+
+  class GetMap {
+    public:
+    typedef GetMapRequest Request;
+    typedef GetMapResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_nav_msgs_GetMapAction_h
+#define _ROS_nav_msgs_GetMapAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/GetMapActionGoal.h"
+#include "nav_msgs/GetMapActionResult.h"
+#include "nav_msgs/GetMapActionFeedback.h"
+
+namespace nav_msgs
+{
+
+  class GetMapAction : public ros::Msg
+  {
+    public:
+      nav_msgs::GetMapActionGoal action_goal;
+      nav_msgs::GetMapActionResult action_result;
+      nav_msgs::GetMapActionFeedback action_feedback;
+
+    GetMapAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapAction"; };
+    const char * getMD5(){ return "e611ad23fbf237c031b7536416dc7cd7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_nav_msgs_GetMapActionFeedback_h
+#define _ROS_nav_msgs_GetMapActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "nav_msgs/GetMapFeedback.h"
+
+namespace nav_msgs
+{
+
+  class GetMapActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      nav_msgs::GetMapFeedback feedback;
+
+    GetMapActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_nav_msgs_GetMapActionGoal_h
+#define _ROS_nav_msgs_GetMapActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "nav_msgs/GetMapGoal.h"
+
+namespace nav_msgs
+{
+
+  class GetMapActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      nav_msgs::GetMapGoal goal;
+
+    GetMapActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapActionGoal"; };
+    const char * getMD5(){ return "4b30be6cd12b9e72826df56b481f40e0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_nav_msgs_GetMapActionResult_h
+#define _ROS_nav_msgs_GetMapActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "nav_msgs/GetMapResult.h"
+
+namespace nav_msgs
+{
+
+  class GetMapActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      nav_msgs::GetMapResult result;
+
+    GetMapActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapActionResult"; };
+    const char * getMD5(){ return "ac66e5b9a79bb4bbd33dab245236c892"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_nav_msgs_GetMapFeedback_h
+#define _ROS_nav_msgs_GetMapFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace nav_msgs
+{
+
+  class GetMapFeedback : public ros::Msg
+  {
+    public:
+
+    GetMapFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_nav_msgs_GetMapGoal_h
+#define _ROS_nav_msgs_GetMapGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace nav_msgs
+{
+
+  class GetMapGoal : public ros::Msg
+  {
+    public:
+
+    GetMapGoal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapGoal"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetMapResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,43 @@
+#ifndef _ROS_nav_msgs_GetMapResult_h
+#define _ROS_nav_msgs_GetMapResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+
+namespace nav_msgs
+{
+
+  class GetMapResult : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid map;
+
+    GetMapResult():
+      map()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GetMapResult"; };
+    const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GetPlan.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetPlan.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,107 @@
+#ifndef _ROS_SERVICE_GetPlan_h
+#define _ROS_SERVICE_GetPlan_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/PoseStamped.h"
+#include "nav_msgs/Path.h"
+
+namespace nav_msgs
+{
+
+static const char GETPLAN[] = "nav_msgs/GetPlan";
+
+  class GetPlanRequest : public ros::Msg
+  {
+    public:
+      geometry_msgs::PoseStamped start;
+      geometry_msgs::PoseStamped goal;
+      float tolerance;
+
+    GetPlanRequest():
+      start(),
+      goal(),
+      tolerance(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->start.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_tolerance;
+      u_tolerance.real = this->tolerance;
+      *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->tolerance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->start.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_tolerance;
+      u_tolerance.base = 0;
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->tolerance = u_tolerance.real;
+      offset += sizeof(this->tolerance);
+     return offset;
+    }
+
+    const char * getType(){ return GETPLAN; };
+    const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; };
+
+  };
+
+  class GetPlanResponse : public ros::Msg
+  {
+    public:
+      nav_msgs::Path plan;
+
+    GetPlanResponse():
+      plan()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->plan.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->plan.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETPLAN; };
+    const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; };
+
+  };
+
+  class GetPlan {
+    public:
+    typedef GetPlanRequest Request;
+    typedef GetPlanResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/GridCells.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GridCells.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,110 @@
+#ifndef _ROS_nav_msgs_GridCells_h
+#define _ROS_nav_msgs_GridCells_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point.h"
+
+namespace nav_msgs
+{
+
+  class GridCells : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      float cell_width;
+      float cell_height;
+      uint8_t cells_length;
+      geometry_msgs::Point st_cells;
+      geometry_msgs::Point * cells;
+
+    GridCells():
+      header(),
+      cell_width(0),
+      cell_height(0),
+      cells_length(0), cells(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_cell_width;
+      u_cell_width.real = this->cell_width;
+      *(outbuffer + offset + 0) = (u_cell_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cell_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cell_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cell_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_width);
+      union {
+        float real;
+        uint32_t base;
+      } u_cell_height;
+      u_cell_height.real = this->cell_height;
+      *(outbuffer + offset + 0) = (u_cell_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cell_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cell_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cell_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_height);
+      *(outbuffer + offset++) = cells_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < cells_length; i++){
+      offset += this->cells[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_cell_width;
+      u_cell_width.base = 0;
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->cell_width = u_cell_width.real;
+      offset += sizeof(this->cell_width);
+      union {
+        float real;
+        uint32_t base;
+      } u_cell_height;
+      u_cell_height.base = 0;
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->cell_height = u_cell_height.real;
+      offset += sizeof(this->cell_height);
+      uint8_t cells_lengthT = *(inbuffer + offset++);
+      if(cells_lengthT > cells_length)
+        this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point));
+      offset += 3;
+      cells_length = cells_lengthT;
+      for( uint8_t i = 0; i < cells_length; i++){
+      offset += this->st_cells.deserialize(inbuffer + offset);
+        memcpy( &(this->cells[i]), &(this->st_cells), sizeof(geometry_msgs::Point));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/GridCells"; };
+    const char * getMD5(){ return "b9e4f5df6d28e272ebde00a3994830f5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/MapMetaData.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/MapMetaData.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,113 @@
+#ifndef _ROS_nav_msgs_MapMetaData_h
+#define _ROS_nav_msgs_MapMetaData_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+#include "geometry_msgs/Pose.h"
+
+namespace nav_msgs
+{
+
+  class MapMetaData : public ros::Msg
+  {
+    public:
+      ros::Time map_load_time;
+      float resolution;
+      uint32_t width;
+      uint32_t height;
+      geometry_msgs::Pose origin;
+
+    MapMetaData():
+      map_load_time(),
+      resolution(0),
+      width(0),
+      height(0),
+      origin()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->map_load_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->map_load_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->map_load_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->map_load_time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->map_load_time.sec);
+      *(outbuffer + offset + 0) = (this->map_load_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->map_load_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->map_load_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->map_load_time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->map_load_time.nsec);
+      union {
+        float real;
+        uint32_t base;
+      } u_resolution;
+      u_resolution.real = this->resolution;
+      *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_resolution.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->resolution);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      offset += this->origin.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->map_load_time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->map_load_time.sec);
+      this->map_load_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->map_load_time.nsec);
+      union {
+        float real;
+        uint32_t base;
+      } u_resolution;
+      u_resolution.base = 0;
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->resolution = u_resolution.real;
+      offset += sizeof(this->resolution);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      offset += this->origin.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/MapMetaData"; };
+    const char * getMD5(){ return "10cfc8a2818024d3248802c00c95f11b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/OccupancyGrid.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/OccupancyGrid.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,81 @@
+#ifndef _ROS_nav_msgs_OccupancyGrid_h
+#define _ROS_nav_msgs_OccupancyGrid_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "nav_msgs/MapMetaData.h"
+
+namespace nav_msgs
+{
+
+  class OccupancyGrid : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      nav_msgs::MapMetaData info;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
+
+    OccupancyGrid():
+      header(),
+      info(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->info.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->info.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/OccupancyGrid"; };
+    const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/Odometry.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Odometry.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_nav_msgs_Odometry_h
+#define _ROS_nav_msgs_Odometry_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/TwistWithCovariance.h"
+
+namespace nav_msgs
+{
+
+  class Odometry : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* child_frame_id;
+      geometry_msgs::PoseWithCovariance pose;
+      geometry_msgs::TwistWithCovariance twist;
+
+    Odometry():
+      header(),
+      child_frame_id(""),
+      pose(),
+      twist()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_child_frame_id = strlen(this->child_frame_id);
+      memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
+      offset += length_child_frame_id;
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_child_frame_id;
+      memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_child_frame_id-1]=0;
+      this->child_frame_id = (char *)(inbuffer + offset-1);
+      offset += length_child_frame_id;
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/Odometry"; };
+    const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/Path.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Path.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_nav_msgs_Path_h
+#define _ROS_nav_msgs_Path_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseStamped.h"
+
+namespace nav_msgs
+{
+
+  class Path : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t poses_length;
+      geometry_msgs::PoseStamped st_poses;
+      geometry_msgs::PoseStamped * poses;
+
+    Path():
+      header(),
+      poses_length(0), poses(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = poses_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t poses_lengthT = *(inbuffer + offset++);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped));
+      offset += 3;
+      poses_length = poses_lengthT;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->st_poses.deserialize(inbuffer + offset);
+        memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "nav_msgs/Path"; };
+    const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 nav_msgs/SetMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/SetMap.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,97 @@
+#ifndef _ROS_SERVICE_SetMap_h
+#define _ROS_SERVICE_SetMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
+
+namespace nav_msgs
+{
+
+static const char SETMAP[] = "nav_msgs/SetMap";
+
+  class SetMapRequest : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid map;
+      geometry_msgs::PoseWithCovarianceStamped initial_pose;
+
+    SetMapRequest():
+      map(),
+      initial_pose()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      offset += this->initial_pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+      offset += this->initial_pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETMAP; };
+    const char * getMD5(){ return "91149a20d7be299b87c340df8cc94fd4"; };
+
+  };
+
+  class SetMapResponse : public ros::Msg
+  {
+    public:
+      bool success;
+
+    SetMapResponse():
+      success(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+     return offset;
+    }
+
+    const char * getType(){ return SETMAP; };
+    const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
+
+  };
+
+  class SetMap {
+    public:
+    typedef SetMapRequest Request;
+    typedef SetMapResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nodelet/NodeletList.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletList.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_NodeletList_h
+#define _ROS_SERVICE_NodeletList_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace nodelet
+{
+
+static const char NODELETLIST[] = "nodelet/NodeletList";
+
+  class NodeletListRequest : public ros::Msg
+  {
+    public:
+
+    NodeletListRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return NODELETLIST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class NodeletListResponse : public ros::Msg
+  {
+    public:
+      uint8_t nodelets_length;
+      char* st_nodelets;
+      char* * nodelets;
+
+    NodeletListResponse():
+      nodelets_length(0), nodelets(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = nodelets_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < nodelets_length; i++){
+      uint32_t length_nodeletsi = strlen(this->nodelets[i]);
+      memcpy(outbuffer + offset, &length_nodeletsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->nodelets[i], length_nodeletsi);
+      offset += length_nodeletsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t nodelets_lengthT = *(inbuffer + offset++);
+      if(nodelets_lengthT > nodelets_length)
+        this->nodelets = (char**)realloc(this->nodelets, nodelets_lengthT * sizeof(char*));
+      offset += 3;
+      nodelets_length = nodelets_lengthT;
+      for( uint8_t i = 0; i < nodelets_length; i++){
+      uint32_t length_st_nodelets;
+      memcpy(&length_st_nodelets, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_nodelets; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_nodelets-1]=0;
+      this->st_nodelets = (char *)(inbuffer + offset-1);
+      offset += length_st_nodelets;
+        memcpy( &(this->nodelets[i]), &(this->st_nodelets), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return NODELETLIST; };
+    const char * getMD5(){ return "99c7b10e794f5600b8030e697e946ca7"; };
+
+  };
+
+  class NodeletList {
+    public:
+    typedef NodeletListRequest Request;
+    typedef NodeletListResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nodelet/NodeletLoad.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletLoad.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,231 @@
+#ifndef _ROS_SERVICE_NodeletLoad_h
+#define _ROS_SERVICE_NodeletLoad_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace nodelet
+{
+
+static const char NODELETLOAD[] = "nodelet/NodeletLoad";
+
+  class NodeletLoadRequest : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* type;
+      uint8_t remap_source_args_length;
+      char* st_remap_source_args;
+      char* * remap_source_args;
+      uint8_t remap_target_args_length;
+      char* st_remap_target_args;
+      char* * remap_target_args;
+      uint8_t my_argv_length;
+      char* st_my_argv;
+      char* * my_argv;
+      const char* bond_id;
+
+    NodeletLoadRequest():
+      name(""),
+      type(""),
+      remap_source_args_length(0), remap_source_args(NULL),
+      remap_target_args_length(0), remap_target_args(NULL),
+      my_argv_length(0), my_argv(NULL),
+      bond_id("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      memcpy(outbuffer + offset, &length_type, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      *(outbuffer + offset++) = remap_source_args_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < remap_source_args_length; i++){
+      uint32_t length_remap_source_argsi = strlen(this->remap_source_args[i]);
+      memcpy(outbuffer + offset, &length_remap_source_argsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->remap_source_args[i], length_remap_source_argsi);
+      offset += length_remap_source_argsi;
+      }
+      *(outbuffer + offset++) = remap_target_args_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < remap_target_args_length; i++){
+      uint32_t length_remap_target_argsi = strlen(this->remap_target_args[i]);
+      memcpy(outbuffer + offset, &length_remap_target_argsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->remap_target_args[i], length_remap_target_argsi);
+      offset += length_remap_target_argsi;
+      }
+      *(outbuffer + offset++) = my_argv_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < my_argv_length; i++){
+      uint32_t length_my_argvi = strlen(this->my_argv[i]);
+      memcpy(outbuffer + offset, &length_my_argvi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->my_argv[i], length_my_argvi);
+      offset += length_my_argvi;
+      }
+      uint32_t length_bond_id = strlen(this->bond_id);
+      memcpy(outbuffer + offset, &length_bond_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->bond_id, length_bond_id);
+      offset += length_bond_id;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_type;
+      memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_type-1]=0;
+      this->type = (char *)(inbuffer + offset-1);
+      offset += length_type;
+      uint8_t remap_source_args_lengthT = *(inbuffer + offset++);
+      if(remap_source_args_lengthT > remap_source_args_length)
+        this->remap_source_args = (char**)realloc(this->remap_source_args, remap_source_args_lengthT * sizeof(char*));
+      offset += 3;
+      remap_source_args_length = remap_source_args_lengthT;
+      for( uint8_t i = 0; i < remap_source_args_length; i++){
+      uint32_t length_st_remap_source_args;
+      memcpy(&length_st_remap_source_args, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_remap_source_args; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_remap_source_args-1]=0;
+      this->st_remap_source_args = (char *)(inbuffer + offset-1);
+      offset += length_st_remap_source_args;
+        memcpy( &(this->remap_source_args[i]), &(this->st_remap_source_args), sizeof(char*));
+      }
+      uint8_t remap_target_args_lengthT = *(inbuffer + offset++);
+      if(remap_target_args_lengthT > remap_target_args_length)
+        this->remap_target_args = (char**)realloc(this->remap_target_args, remap_target_args_lengthT * sizeof(char*));
+      offset += 3;
+      remap_target_args_length = remap_target_args_lengthT;
+      for( uint8_t i = 0; i < remap_target_args_length; i++){
+      uint32_t length_st_remap_target_args;
+      memcpy(&length_st_remap_target_args, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_remap_target_args; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_remap_target_args-1]=0;
+      this->st_remap_target_args = (char *)(inbuffer + offset-1);
+      offset += length_st_remap_target_args;
+        memcpy( &(this->remap_target_args[i]), &(this->st_remap_target_args), sizeof(char*));
+      }
+      uint8_t my_argv_lengthT = *(inbuffer + offset++);
+      if(my_argv_lengthT > my_argv_length)
+        this->my_argv = (char**)realloc(this->my_argv, my_argv_lengthT * sizeof(char*));
+      offset += 3;
+      my_argv_length = my_argv_lengthT;
+      for( uint8_t i = 0; i < my_argv_length; i++){
+      uint32_t length_st_my_argv;
+      memcpy(&length_st_my_argv, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_my_argv; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_my_argv-1]=0;
+      this->st_my_argv = (char *)(inbuffer + offset-1);
+      offset += length_st_my_argv;
+        memcpy( &(this->my_argv[i]), &(this->st_my_argv), sizeof(char*));
+      }
+      uint32_t length_bond_id;
+      memcpy(&length_bond_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_bond_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_bond_id-1]=0;
+      this->bond_id = (char *)(inbuffer + offset-1);
+      offset += length_bond_id;
+     return offset;
+    }
+
+    const char * getType(){ return NODELETLOAD; };
+    const char * getMD5(){ return "c6e28cc4d2e259249d96cfb50658fbec"; };
+
+  };
+
+  class NodeletLoadResponse : public ros::Msg
+  {
+    public:
+      bool success;
+
+    NodeletLoadResponse():
+      success(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+     return offset;
+    }
+
+    const char * getType(){ return NODELETLOAD; };
+    const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
+
+  };
+
+  class NodeletLoad {
+    public:
+    typedef NodeletLoadRequest Request;
+    typedef NodeletLoadResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 nodelet/NodeletUnload.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletUnload.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,103 @@
+#ifndef _ROS_SERVICE_NodeletUnload_h
+#define _ROS_SERVICE_NodeletUnload_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace nodelet
+{
+
+static const char NODELETUNLOAD[] = "nodelet/NodeletUnload";
+
+  class NodeletUnloadRequest : public ros::Msg
+  {
+    public:
+      const char* name;
+
+    NodeletUnloadRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return NODELETUNLOAD; };
+    const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
+
+  };
+
+  class NodeletUnloadResponse : public ros::Msg
+  {
+    public:
+      bool success;
+
+    NodeletUnloadResponse():
+      success(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+     return offset;
+    }
+
+    const char * getType(){ return NODELETUNLOAD; };
+    const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
+
+  };
+
+  class NodeletUnload {
+    public:
+    typedef NodeletUnloadRequest Request;
+    typedef NodeletUnloadResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Circle.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Circle.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,74 @@
+#ifndef _ROS_opencv_apps_Circle_h
+#define _ROS_opencv_apps_Circle_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Circle : public ros::Msg
+  {
+    public:
+      opencv_apps::Point2D center;
+      double radius;
+
+    Circle():
+      center(),
+      radius(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->center.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_radius;
+      u_radius.real = this->radius;
+      *(outbuffer + offset + 0) = (u_radius.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_radius.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_radius.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_radius.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_radius.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_radius.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_radius.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_radius.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->radius);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->center.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_radius;
+      u_radius.base = 0;
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_radius.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->radius = u_radius.real;
+      offset += sizeof(this->radius);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Circle"; };
+    const char * getMD5(){ return "4f6847051b4fe493b5af8caad66201d5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/CircleArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/CircleArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_CircleArray_h
+#define _ROS_opencv_apps_CircleArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Circle.h"
+
+namespace opencv_apps
+{
+
+  class CircleArray : public ros::Msg
+  {
+    public:
+      uint8_t circles_length;
+      opencv_apps::Circle st_circles;
+      opencv_apps::Circle * circles;
+
+    CircleArray():
+      circles_length(0), circles(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = circles_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < circles_length; i++){
+      offset += this->circles[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t circles_lengthT = *(inbuffer + offset++);
+      if(circles_lengthT > circles_length)
+        this->circles = (opencv_apps::Circle*)realloc(this->circles, circles_lengthT * sizeof(opencv_apps::Circle));
+      offset += 3;
+      circles_length = circles_lengthT;
+      for( uint8_t i = 0; i < circles_length; i++){
+      offset += this->st_circles.deserialize(inbuffer + offset);
+        memcpy( &(this->circles[i]), &(this->st_circles), sizeof(opencv_apps::Circle));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/CircleArray"; };
+    const char * getMD5(){ return "1970b146e338dd024c765e522039a727"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/CircleArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/CircleArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_CircleArrayStamped_h
+#define _ROS_opencv_apps_CircleArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Circle.h"
+
+namespace opencv_apps
+{
+
+  class CircleArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t circles_length;
+      opencv_apps::Circle st_circles;
+      opencv_apps::Circle * circles;
+
+    CircleArrayStamped():
+      header(),
+      circles_length(0), circles(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = circles_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < circles_length; i++){
+      offset += this->circles[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t circles_lengthT = *(inbuffer + offset++);
+      if(circles_lengthT > circles_length)
+        this->circles = (opencv_apps::Circle*)realloc(this->circles, circles_lengthT * sizeof(opencv_apps::Circle));
+      offset += 3;
+      circles_length = circles_lengthT;
+      for( uint8_t i = 0; i < circles_length; i++){
+      offset += this->st_circles.deserialize(inbuffer + offset);
+        memcpy( &(this->circles[i]), &(this->st_circles), sizeof(opencv_apps::Circle));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/CircleArrayStamped"; };
+    const char * getMD5(){ return "430ffa6c2b0a36b7e81feff1ce79c3c4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Contour.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Contour.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_Contour_h
+#define _ROS_opencv_apps_Contour_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Contour : public ros::Msg
+  {
+    public:
+      uint8_t points_length;
+      opencv_apps::Point2D st_points;
+      opencv_apps::Point2D * points;
+
+    Contour():
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (opencv_apps::Point2D*)realloc(this->points, points_lengthT * sizeof(opencv_apps::Point2D));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(opencv_apps::Point2D));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Contour"; };
+    const char * getMD5(){ return "8f02263beef99aa03117a577a3eb879d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/ContourArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/ContourArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_ContourArray_h
+#define _ROS_opencv_apps_ContourArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Contour.h"
+
+namespace opencv_apps
+{
+
+  class ContourArray : public ros::Msg
+  {
+    public:
+      uint8_t contours_length;
+      opencv_apps::Contour st_contours;
+      opencv_apps::Contour * contours;
+
+    ContourArray():
+      contours_length(0), contours(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = contours_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < contours_length; i++){
+      offset += this->contours[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t contours_lengthT = *(inbuffer + offset++);
+      if(contours_lengthT > contours_length)
+        this->contours = (opencv_apps::Contour*)realloc(this->contours, contours_lengthT * sizeof(opencv_apps::Contour));
+      offset += 3;
+      contours_length = contours_lengthT;
+      for( uint8_t i = 0; i < contours_length; i++){
+      offset += this->st_contours.deserialize(inbuffer + offset);
+        memcpy( &(this->contours[i]), &(this->st_contours), sizeof(opencv_apps::Contour));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/ContourArray"; };
+    const char * getMD5(){ return "fc54374f45559dfed248b316ccf9181d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/ContourArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/ContourArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_ContourArrayStamped_h
+#define _ROS_opencv_apps_ContourArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Contour.h"
+
+namespace opencv_apps
+{
+
+  class ContourArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t contours_length;
+      opencv_apps::Contour st_contours;
+      opencv_apps::Contour * contours;
+
+    ContourArrayStamped():
+      header(),
+      contours_length(0), contours(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = contours_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < contours_length; i++){
+      offset += this->contours[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t contours_lengthT = *(inbuffer + offset++);
+      if(contours_lengthT > contours_length)
+        this->contours = (opencv_apps::Contour*)realloc(this->contours, contours_lengthT * sizeof(opencv_apps::Contour));
+      offset += 3;
+      contours_length = contours_lengthT;
+      for( uint8_t i = 0; i < contours_length; i++){
+      offset += this->st_contours.deserialize(inbuffer + offset);
+        memcpy( &(this->contours[i]), &(this->st_contours), sizeof(opencv_apps::Contour));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/ContourArrayStamped"; };
+    const char * getMD5(){ return "6bcf2733566be102cf11fc89685fd962"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Face.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Face.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,63 @@
+#ifndef _ROS_opencv_apps_Face_h
+#define _ROS_opencv_apps_Face_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Rect.h"
+
+namespace opencv_apps
+{
+
+  class Face : public ros::Msg
+  {
+    public:
+      opencv_apps::Rect face;
+      uint8_t eyes_length;
+      opencv_apps::Rect st_eyes;
+      opencv_apps::Rect * eyes;
+
+    Face():
+      face(),
+      eyes_length(0), eyes(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->face.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = eyes_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < eyes_length; i++){
+      offset += this->eyes[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->face.deserialize(inbuffer + offset);
+      uint8_t eyes_lengthT = *(inbuffer + offset++);
+      if(eyes_lengthT > eyes_length)
+        this->eyes = (opencv_apps::Rect*)realloc(this->eyes, eyes_lengthT * sizeof(opencv_apps::Rect));
+      offset += 3;
+      eyes_length = eyes_lengthT;
+      for( uint8_t i = 0; i < eyes_length; i++){
+      offset += this->st_eyes.deserialize(inbuffer + offset);
+        memcpy( &(this->eyes[i]), &(this->st_eyes), sizeof(opencv_apps::Rect));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Face"; };
+    const char * getMD5(){ return "0c2547d2eaf71219898bf5c25e36907e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/FaceArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/FaceArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_FaceArray_h
+#define _ROS_opencv_apps_FaceArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Face.h"
+
+namespace opencv_apps
+{
+
+  class FaceArray : public ros::Msg
+  {
+    public:
+      uint8_t faces_length;
+      opencv_apps::Face st_faces;
+      opencv_apps::Face * faces;
+
+    FaceArray():
+      faces_length(0), faces(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = faces_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < faces_length; i++){
+      offset += this->faces[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t faces_lengthT = *(inbuffer + offset++);
+      if(faces_lengthT > faces_length)
+        this->faces = (opencv_apps::Face*)realloc(this->faces, faces_lengthT * sizeof(opencv_apps::Face));
+      offset += 3;
+      faces_length = faces_lengthT;
+      for( uint8_t i = 0; i < faces_length; i++){
+      offset += this->st_faces.deserialize(inbuffer + offset);
+        memcpy( &(this->faces[i]), &(this->st_faces), sizeof(opencv_apps::Face));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/FaceArray"; };
+    const char * getMD5(){ return "40b464276ad8e3c5012f7a3a93eed2a4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/FaceArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/FaceArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_FaceArrayStamped_h
+#define _ROS_opencv_apps_FaceArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Face.h"
+
+namespace opencv_apps
+{
+
+  class FaceArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t faces_length;
+      opencv_apps::Face st_faces;
+      opencv_apps::Face * faces;
+
+    FaceArrayStamped():
+      header(),
+      faces_length(0), faces(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = faces_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < faces_length; i++){
+      offset += this->faces[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t faces_lengthT = *(inbuffer + offset++);
+      if(faces_lengthT > faces_length)
+        this->faces = (opencv_apps::Face*)realloc(this->faces, faces_lengthT * sizeof(opencv_apps::Face));
+      offset += 3;
+      faces_length = faces_lengthT;
+      for( uint8_t i = 0; i < faces_length; i++){
+      offset += this->st_faces.deserialize(inbuffer + offset);
+        memcpy( &(this->faces[i]), &(this->st_faces), sizeof(opencv_apps::Face));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/FaceArrayStamped"; };
+    const char * getMD5(){ return "bf258edc868c139ea6c94254d9ab51e5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Flow.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Flow.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,47 @@
+#ifndef _ROS_opencv_apps_Flow_h
+#define _ROS_opencv_apps_Flow_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Flow : public ros::Msg
+  {
+    public:
+      opencv_apps::Point2D point;
+      opencv_apps::Point2D velocity;
+
+    Flow():
+      point(),
+      velocity()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->point.serialize(outbuffer + offset);
+      offset += this->velocity.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->point.deserialize(inbuffer + offset);
+      offset += this->velocity.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Flow"; };
+    const char * getMD5(){ return "dd9a9efd88ba39035e78af697593d751"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/FlowArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/FlowArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_FlowArray_h
+#define _ROS_opencv_apps_FlowArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Flow.h"
+
+namespace opencv_apps
+{
+
+  class FlowArray : public ros::Msg
+  {
+    public:
+      uint8_t flow_length;
+      opencv_apps::Flow st_flow;
+      opencv_apps::Flow * flow;
+
+    FlowArray():
+      flow_length(0), flow(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = flow_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < flow_length; i++){
+      offset += this->flow[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t flow_lengthT = *(inbuffer + offset++);
+      if(flow_lengthT > flow_length)
+        this->flow = (opencv_apps::Flow*)realloc(this->flow, flow_lengthT * sizeof(opencv_apps::Flow));
+      offset += 3;
+      flow_length = flow_lengthT;
+      for( uint8_t i = 0; i < flow_length; i++){
+      offset += this->st_flow.deserialize(inbuffer + offset);
+        memcpy( &(this->flow[i]), &(this->st_flow), sizeof(opencv_apps::Flow));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/FlowArray"; };
+    const char * getMD5(){ return "fe292dca56eb3673cd698ea9ef841962"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/FlowArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/FlowArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_FlowArrayStamped_h
+#define _ROS_opencv_apps_FlowArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Flow.h"
+
+namespace opencv_apps
+{
+
+  class FlowArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t flow_length;
+      opencv_apps::Flow st_flow;
+      opencv_apps::Flow * flow;
+
+    FlowArrayStamped():
+      header(),
+      flow_length(0), flow(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = flow_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < flow_length; i++){
+      offset += this->flow[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t flow_lengthT = *(inbuffer + offset++);
+      if(flow_lengthT > flow_length)
+        this->flow = (opencv_apps::Flow*)realloc(this->flow, flow_lengthT * sizeof(opencv_apps::Flow));
+      offset += 3;
+      flow_length = flow_lengthT;
+      for( uint8_t i = 0; i < flow_length; i++){
+      offset += this->st_flow.deserialize(inbuffer + offset);
+        memcpy( &(this->flow[i]), &(this->st_flow), sizeof(opencv_apps::Flow));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/FlowArrayStamped"; };
+    const char * getMD5(){ return "b55faf909449963372b92417925b68cc"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/FlowStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/FlowStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_opencv_apps_FlowStamped_h
+#define _ROS_opencv_apps_FlowStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Flow.h"
+
+namespace opencv_apps
+{
+
+  class FlowStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      opencv_apps::Flow flow;
+
+    FlowStamped():
+      header(),
+      flow()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->flow.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->flow.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/FlowStamped"; };
+    const char * getMD5(){ return "b55faf909449963372b92417925b68cc"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Line.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Line.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,47 @@
+#ifndef _ROS_opencv_apps_Line_h
+#define _ROS_opencv_apps_Line_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Line : public ros::Msg
+  {
+    public:
+      opencv_apps::Point2D pt1;
+      opencv_apps::Point2D pt2;
+
+    Line():
+      pt1(),
+      pt2()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->pt1.serialize(outbuffer + offset);
+      offset += this->pt2.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->pt1.deserialize(inbuffer + offset);
+      offset += this->pt2.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Line"; };
+    const char * getMD5(){ return "a1419010b3fc4549e3f450018363d000"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/LineArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/LineArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_LineArray_h
+#define _ROS_opencv_apps_LineArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Line.h"
+
+namespace opencv_apps
+{
+
+  class LineArray : public ros::Msg
+  {
+    public:
+      uint8_t lines_length;
+      opencv_apps::Line st_lines;
+      opencv_apps::Line * lines;
+
+    LineArray():
+      lines_length(0), lines(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = lines_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < lines_length; i++){
+      offset += this->lines[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t lines_lengthT = *(inbuffer + offset++);
+      if(lines_lengthT > lines_length)
+        this->lines = (opencv_apps::Line*)realloc(this->lines, lines_lengthT * sizeof(opencv_apps::Line));
+      offset += 3;
+      lines_length = lines_lengthT;
+      for( uint8_t i = 0; i < lines_length; i++){
+      offset += this->st_lines.deserialize(inbuffer + offset);
+        memcpy( &(this->lines[i]), &(this->st_lines), sizeof(opencv_apps::Line));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/LineArray"; };
+    const char * getMD5(){ return "2b5441933900cc71528395dda29124da"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/LineArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/LineArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_LineArrayStamped_h
+#define _ROS_opencv_apps_LineArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Line.h"
+
+namespace opencv_apps
+{
+
+  class LineArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t lines_length;
+      opencv_apps::Line st_lines;
+      opencv_apps::Line * lines;
+
+    LineArrayStamped():
+      header(),
+      lines_length(0), lines(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = lines_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < lines_length; i++){
+      offset += this->lines[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t lines_lengthT = *(inbuffer + offset++);
+      if(lines_lengthT > lines_length)
+        this->lines = (opencv_apps::Line*)realloc(this->lines, lines_lengthT * sizeof(opencv_apps::Line));
+      offset += 3;
+      lines_length = lines_lengthT;
+      for( uint8_t i = 0; i < lines_length; i++){
+      offset += this->st_lines.deserialize(inbuffer + offset);
+        memcpy( &(this->lines[i]), &(this->st_lines), sizeof(opencv_apps::Line));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/LineArrayStamped"; };
+    const char * getMD5(){ return "8ad5d104256b4f6774479453d1118f74"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Moment.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Moment.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,849 @@
+#ifndef _ROS_opencv_apps_Moment_h
+#define _ROS_opencv_apps_Moment_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Moment : public ros::Msg
+  {
+    public:
+      double m00;
+      double m10;
+      double m01;
+      double m20;
+      double m11;
+      double m02;
+      double m30;
+      double m21;
+      double m12;
+      double m03;
+      double mu20;
+      double mu11;
+      double mu02;
+      double mu30;
+      double mu21;
+      double mu12;
+      double mu03;
+      double nu20;
+      double nu11;
+      double nu02;
+      double nu30;
+      double nu21;
+      double nu12;
+      double nu03;
+      opencv_apps::Point2D center;
+      double length;
+      double area;
+
+    Moment():
+      m00(0),
+      m10(0),
+      m01(0),
+      m20(0),
+      m11(0),
+      m02(0),
+      m30(0),
+      m21(0),
+      m12(0),
+      m03(0),
+      mu20(0),
+      mu11(0),
+      mu02(0),
+      mu30(0),
+      mu21(0),
+      mu12(0),
+      mu03(0),
+      nu20(0),
+      nu11(0),
+      nu02(0),
+      nu30(0),
+      nu21(0),
+      nu12(0),
+      nu03(0),
+      center(),
+      length(0),
+      area(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_m00;
+      u_m00.real = this->m00;
+      *(outbuffer + offset + 0) = (u_m00.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m00.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m00.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m00.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m00.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m00.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m00.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m00.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m00);
+      union {
+        double real;
+        uint64_t base;
+      } u_m10;
+      u_m10.real = this->m10;
+      *(outbuffer + offset + 0) = (u_m10.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m10.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m10.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m10.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m10.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m10.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m10.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m10.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m10);
+      union {
+        double real;
+        uint64_t base;
+      } u_m01;
+      u_m01.real = this->m01;
+      *(outbuffer + offset + 0) = (u_m01.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m01.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m01.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m01.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m01.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m01.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m01.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m01.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m01);
+      union {
+        double real;
+        uint64_t base;
+      } u_m20;
+      u_m20.real = this->m20;
+      *(outbuffer + offset + 0) = (u_m20.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m20.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m20.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m20.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m20.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m20.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m20.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m20.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m20);
+      union {
+        double real;
+        uint64_t base;
+      } u_m11;
+      u_m11.real = this->m11;
+      *(outbuffer + offset + 0) = (u_m11.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m11.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m11.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m11.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m11.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m11.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m11.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m11.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m11);
+      union {
+        double real;
+        uint64_t base;
+      } u_m02;
+      u_m02.real = this->m02;
+      *(outbuffer + offset + 0) = (u_m02.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m02.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m02.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m02.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m02.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m02.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m02.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m02.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m02);
+      union {
+        double real;
+        uint64_t base;
+      } u_m30;
+      u_m30.real = this->m30;
+      *(outbuffer + offset + 0) = (u_m30.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m30.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m30.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m30.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m30.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m30.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m30.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m30.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m30);
+      union {
+        double real;
+        uint64_t base;
+      } u_m21;
+      u_m21.real = this->m21;
+      *(outbuffer + offset + 0) = (u_m21.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m21.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m21.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m21.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m21.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m21.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m21.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m21.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m21);
+      union {
+        double real;
+        uint64_t base;
+      } u_m12;
+      u_m12.real = this->m12;
+      *(outbuffer + offset + 0) = (u_m12.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m12.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m12.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m12.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m12.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m12.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m12.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m12.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m12);
+      union {
+        double real;
+        uint64_t base;
+      } u_m03;
+      u_m03.real = this->m03;
+      *(outbuffer + offset + 0) = (u_m03.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_m03.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_m03.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_m03.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_m03.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_m03.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_m03.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_m03.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->m03);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu20;
+      u_mu20.real = this->mu20;
+      *(outbuffer + offset + 0) = (u_mu20.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu20.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu20.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu20.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu20.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu20.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu20.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu20.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu20);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu11;
+      u_mu11.real = this->mu11;
+      *(outbuffer + offset + 0) = (u_mu11.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu11.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu11.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu11.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu11.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu11.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu11.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu11.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu11);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu02;
+      u_mu02.real = this->mu02;
+      *(outbuffer + offset + 0) = (u_mu02.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu02.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu02.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu02.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu02.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu02.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu02.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu02.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu02);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu30;
+      u_mu30.real = this->mu30;
+      *(outbuffer + offset + 0) = (u_mu30.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu30.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu30.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu30.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu30.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu30.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu30.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu30.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu30);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu21;
+      u_mu21.real = this->mu21;
+      *(outbuffer + offset + 0) = (u_mu21.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu21.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu21.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu21.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu21.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu21.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu21.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu21.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu21);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu12;
+      u_mu12.real = this->mu12;
+      *(outbuffer + offset + 0) = (u_mu12.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu12.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu12.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu12.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu12.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu12.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu12.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu12.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu12);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu03;
+      u_mu03.real = this->mu03;
+      *(outbuffer + offset + 0) = (u_mu03.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_mu03.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_mu03.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_mu03.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_mu03.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_mu03.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_mu03.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_mu03.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->mu03);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu20;
+      u_nu20.real = this->nu20;
+      *(outbuffer + offset + 0) = (u_nu20.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu20.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu20.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu20.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu20.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu20.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu20.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu20.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu20);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu11;
+      u_nu11.real = this->nu11;
+      *(outbuffer + offset + 0) = (u_nu11.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu11.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu11.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu11.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu11.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu11.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu11.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu11.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu11);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu02;
+      u_nu02.real = this->nu02;
+      *(outbuffer + offset + 0) = (u_nu02.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu02.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu02.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu02.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu02.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu02.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu02.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu02.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu02);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu30;
+      u_nu30.real = this->nu30;
+      *(outbuffer + offset + 0) = (u_nu30.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu30.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu30.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu30.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu30.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu30.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu30.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu30.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu30);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu21;
+      u_nu21.real = this->nu21;
+      *(outbuffer + offset + 0) = (u_nu21.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu21.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu21.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu21.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu21.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu21.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu21.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu21.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu21);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu12;
+      u_nu12.real = this->nu12;
+      *(outbuffer + offset + 0) = (u_nu12.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu12.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu12.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu12.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu12.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu12.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu12.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu12.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu12);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu03;
+      u_nu03.real = this->nu03;
+      *(outbuffer + offset + 0) = (u_nu03.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nu03.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nu03.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nu03.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_nu03.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_nu03.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_nu03.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_nu03.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->nu03);
+      offset += this->center.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_length;
+      u_length.real = this->length;
+      *(outbuffer + offset + 0) = (u_length.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_length.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_length.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_length.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_length.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_length.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_length.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_length.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->length);
+      union {
+        double real;
+        uint64_t base;
+      } u_area;
+      u_area.real = this->area;
+      *(outbuffer + offset + 0) = (u_area.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_area.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_area.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_area.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_area.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_area.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_area.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_area.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->area);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_m00;
+      u_m00.base = 0;
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m00.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m00 = u_m00.real;
+      offset += sizeof(this->m00);
+      union {
+        double real;
+        uint64_t base;
+      } u_m10;
+      u_m10.base = 0;
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m10.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m10 = u_m10.real;
+      offset += sizeof(this->m10);
+      union {
+        double real;
+        uint64_t base;
+      } u_m01;
+      u_m01.base = 0;
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m01.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m01 = u_m01.real;
+      offset += sizeof(this->m01);
+      union {
+        double real;
+        uint64_t base;
+      } u_m20;
+      u_m20.base = 0;
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m20.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m20 = u_m20.real;
+      offset += sizeof(this->m20);
+      union {
+        double real;
+        uint64_t base;
+      } u_m11;
+      u_m11.base = 0;
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m11.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m11 = u_m11.real;
+      offset += sizeof(this->m11);
+      union {
+        double real;
+        uint64_t base;
+      } u_m02;
+      u_m02.base = 0;
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m02.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m02 = u_m02.real;
+      offset += sizeof(this->m02);
+      union {
+        double real;
+        uint64_t base;
+      } u_m30;
+      u_m30.base = 0;
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m30.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m30 = u_m30.real;
+      offset += sizeof(this->m30);
+      union {
+        double real;
+        uint64_t base;
+      } u_m21;
+      u_m21.base = 0;
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m21.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m21 = u_m21.real;
+      offset += sizeof(this->m21);
+      union {
+        double real;
+        uint64_t base;
+      } u_m12;
+      u_m12.base = 0;
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m12.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m12 = u_m12.real;
+      offset += sizeof(this->m12);
+      union {
+        double real;
+        uint64_t base;
+      } u_m03;
+      u_m03.base = 0;
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_m03.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->m03 = u_m03.real;
+      offset += sizeof(this->m03);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu20;
+      u_mu20.base = 0;
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu20.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu20 = u_mu20.real;
+      offset += sizeof(this->mu20);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu11;
+      u_mu11.base = 0;
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu11.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu11 = u_mu11.real;
+      offset += sizeof(this->mu11);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu02;
+      u_mu02.base = 0;
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu02.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu02 = u_mu02.real;
+      offset += sizeof(this->mu02);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu30;
+      u_mu30.base = 0;
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu30.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu30 = u_mu30.real;
+      offset += sizeof(this->mu30);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu21;
+      u_mu21.base = 0;
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu21.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu21 = u_mu21.real;
+      offset += sizeof(this->mu21);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu12;
+      u_mu12.base = 0;
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu12.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu12 = u_mu12.real;
+      offset += sizeof(this->mu12);
+      union {
+        double real;
+        uint64_t base;
+      } u_mu03;
+      u_mu03.base = 0;
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_mu03.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->mu03 = u_mu03.real;
+      offset += sizeof(this->mu03);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu20;
+      u_nu20.base = 0;
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu20.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu20 = u_nu20.real;
+      offset += sizeof(this->nu20);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu11;
+      u_nu11.base = 0;
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu11.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu11 = u_nu11.real;
+      offset += sizeof(this->nu11);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu02;
+      u_nu02.base = 0;
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu02.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu02 = u_nu02.real;
+      offset += sizeof(this->nu02);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu30;
+      u_nu30.base = 0;
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu30.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu30 = u_nu30.real;
+      offset += sizeof(this->nu30);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu21;
+      u_nu21.base = 0;
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu21.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu21 = u_nu21.real;
+      offset += sizeof(this->nu21);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu12;
+      u_nu12.base = 0;
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu12.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu12 = u_nu12.real;
+      offset += sizeof(this->nu12);
+      union {
+        double real;
+        uint64_t base;
+      } u_nu03;
+      u_nu03.base = 0;
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_nu03.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->nu03 = u_nu03.real;
+      offset += sizeof(this->nu03);
+      offset += this->center.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_length;
+      u_length.base = 0;
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_length.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->length = u_length.real;
+      offset += sizeof(this->length);
+      union {
+        double real;
+        uint64_t base;
+      } u_area;
+      u_area.base = 0;
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_area.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->area = u_area.real;
+      offset += sizeof(this->area);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Moment"; };
+    const char * getMD5(){ return "560ee3fabfffb4ed4155742d6db8a03c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/MomentArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/MomentArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_MomentArray_h
+#define _ROS_opencv_apps_MomentArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Moment.h"
+
+namespace opencv_apps
+{
+
+  class MomentArray : public ros::Msg
+  {
+    public:
+      uint8_t moments_length;
+      opencv_apps::Moment st_moments;
+      opencv_apps::Moment * moments;
+
+    MomentArray():
+      moments_length(0), moments(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = moments_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < moments_length; i++){
+      offset += this->moments[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t moments_lengthT = *(inbuffer + offset++);
+      if(moments_lengthT > moments_length)
+        this->moments = (opencv_apps::Moment*)realloc(this->moments, moments_lengthT * sizeof(opencv_apps::Moment));
+      offset += 3;
+      moments_length = moments_lengthT;
+      for( uint8_t i = 0; i < moments_length; i++){
+      offset += this->st_moments.deserialize(inbuffer + offset);
+        memcpy( &(this->moments[i]), &(this->st_moments), sizeof(opencv_apps::Moment));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/MomentArray"; };
+    const char * getMD5(){ return "fb51ddd1dea5da45f56842efe759d448"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/MomentArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/MomentArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_MomentArrayStamped_h
+#define _ROS_opencv_apps_MomentArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Moment.h"
+
+namespace opencv_apps
+{
+
+  class MomentArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t moments_length;
+      opencv_apps::Moment st_moments;
+      opencv_apps::Moment * moments;
+
+    MomentArrayStamped():
+      header(),
+      moments_length(0), moments(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = moments_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < moments_length; i++){
+      offset += this->moments[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t moments_lengthT = *(inbuffer + offset++);
+      if(moments_lengthT > moments_length)
+        this->moments = (opencv_apps::Moment*)realloc(this->moments, moments_lengthT * sizeof(opencv_apps::Moment));
+      offset += 3;
+      moments_length = moments_lengthT;
+      for( uint8_t i = 0; i < moments_length; i++){
+      offset += this->st_moments.deserialize(inbuffer + offset);
+        memcpy( &(this->moments[i]), &(this->st_moments), sizeof(opencv_apps::Moment));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/MomentArrayStamped"; };
+    const char * getMD5(){ return "28ac0beb70b037acf76c3bed71b679a9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Point2D.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Point2D.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_opencv_apps_Point2D_h
+#define _ROS_opencv_apps_Point2D_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace opencv_apps
+{
+
+  class Point2D : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+
+    Point2D():
+      x(0),
+      y(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Point2D"; };
+    const char * getMD5(){ return "209f516d3eb691f0663e25cb750d67c1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Point2DArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Point2DArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_Point2DArray_h
+#define _ROS_opencv_apps_Point2DArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Point2DArray : public ros::Msg
+  {
+    public:
+      uint8_t points_length;
+      opencv_apps::Point2D st_points;
+      opencv_apps::Point2D * points;
+
+    Point2DArray():
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (opencv_apps::Point2D*)realloc(this->points, points_lengthT * sizeof(opencv_apps::Point2D));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(opencv_apps::Point2D));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Point2DArray"; };
+    const char * getMD5(){ return "8f02263beef99aa03117a577a3eb879d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Point2DArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Point2DArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_Point2DArrayStamped_h
+#define _ROS_opencv_apps_Point2DArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Point2DArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t points_length;
+      opencv_apps::Point2D st_points;
+      opencv_apps::Point2D * points;
+
+    Point2DArrayStamped():
+      header(),
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (opencv_apps::Point2D*)realloc(this->points, points_lengthT * sizeof(opencv_apps::Point2D));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(opencv_apps::Point2D));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Point2DArrayStamped"; };
+    const char * getMD5(){ return "06c8694bd7b07dbc04014c86ef9991a2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Point2DStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Point2DStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_opencv_apps_Point2DStamped_h
+#define _ROS_opencv_apps_Point2DStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Point2D.h"
+
+namespace opencv_apps
+{
+
+  class Point2DStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      opencv_apps::Point2D point;
+
+    Point2DStamped():
+      header(),
+      point()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->point.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->point.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Point2DStamped"; };
+    const char * getMD5(){ return "9f7db918fde9989a73131d0d083d049d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Rect.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Rect.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,162 @@
+#ifndef _ROS_opencv_apps_Rect_h
+#define _ROS_opencv_apps_Rect_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace opencv_apps
+{
+
+  class Rect : public ros::Msg
+  {
+    public:
+      double x;
+      double y;
+      double width;
+      double height;
+
+    Rect():
+      x(0),
+      y(0),
+      width(0),
+      height(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_width.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_width.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_width.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_width.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_height.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_height.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_height.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_height.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->height);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        double real;
+        uint64_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Rect"; };
+    const char * getMD5(){ return "7048f28f1f0ef51e102638c86d9a7728"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RectArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RectArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_RectArray_h
+#define _ROS_opencv_apps_RectArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Rect.h"
+
+namespace opencv_apps
+{
+
+  class RectArray : public ros::Msg
+  {
+    public:
+      uint8_t rects_length;
+      opencv_apps::Rect st_rects;
+      opencv_apps::Rect * rects;
+
+    RectArray():
+      rects_length(0), rects(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = rects_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->rects[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t rects_lengthT = *(inbuffer + offset++);
+      if(rects_lengthT > rects_length)
+        this->rects = (opencv_apps::Rect*)realloc(this->rects, rects_lengthT * sizeof(opencv_apps::Rect));
+      offset += 3;
+      rects_length = rects_lengthT;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->st_rects.deserialize(inbuffer + offset);
+        memcpy( &(this->rects[i]), &(this->st_rects), sizeof(opencv_apps::Rect));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RectArray"; };
+    const char * getMD5(){ return "d4a6f20c7699fa2791af675958a5f148"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RectArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RectArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_RectArrayStamped_h
+#define _ROS_opencv_apps_RectArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/Rect.h"
+
+namespace opencv_apps
+{
+
+  class RectArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t rects_length;
+      opencv_apps::Rect st_rects;
+      opencv_apps::Rect * rects;
+
+    RectArrayStamped():
+      header(),
+      rects_length(0), rects(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = rects_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->rects[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t rects_lengthT = *(inbuffer + offset++);
+      if(rects_lengthT > rects_length)
+        this->rects = (opencv_apps::Rect*)realloc(this->rects, rects_lengthT * sizeof(opencv_apps::Rect));
+      offset += 3;
+      rects_length = rects_lengthT;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->st_rects.deserialize(inbuffer + offset);
+        memcpy( &(this->rects[i]), &(this->st_rects), sizeof(opencv_apps::Rect));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RectArrayStamped"; };
+    const char * getMD5(){ return "f29b08b33e061c73d7d9fc35142631d0"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RotatedRect.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RotatedRect.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,79 @@
+#ifndef _ROS_opencv_apps_RotatedRect_h
+#define _ROS_opencv_apps_RotatedRect_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/Point2D.h"
+#include "opencv_apps/Size.h"
+
+namespace opencv_apps
+{
+
+  class RotatedRect : public ros::Msg
+  {
+    public:
+      double angle;
+      opencv_apps::Point2D center;
+      opencv_apps::Size size;
+
+    RotatedRect():
+      angle(0),
+      center(),
+      size()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_angle;
+      u_angle.real = this->angle;
+      *(outbuffer + offset + 0) = (u_angle.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_angle.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_angle.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_angle.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_angle.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->angle);
+      offset += this->center.serialize(outbuffer + offset);
+      offset += this->size.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_angle;
+      u_angle.base = 0;
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_angle.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->angle = u_angle.real;
+      offset += sizeof(this->angle);
+      offset += this->center.deserialize(inbuffer + offset);
+      offset += this->size.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RotatedRect"; };
+    const char * getMD5(){ return "0ae60505c52f020176686d0689b8d390"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RotatedRectArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RotatedRectArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_opencv_apps_RotatedRectArray_h
+#define _ROS_opencv_apps_RotatedRectArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "opencv_apps/RotatedRect.h"
+
+namespace opencv_apps
+{
+
+  class RotatedRectArray : public ros::Msg
+  {
+    public:
+      uint8_t rects_length;
+      opencv_apps::RotatedRect st_rects;
+      opencv_apps::RotatedRect * rects;
+
+    RotatedRectArray():
+      rects_length(0), rects(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = rects_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->rects[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t rects_lengthT = *(inbuffer + offset++);
+      if(rects_lengthT > rects_length)
+        this->rects = (opencv_apps::RotatedRect*)realloc(this->rects, rects_lengthT * sizeof(opencv_apps::RotatedRect));
+      offset += 3;
+      rects_length = rects_lengthT;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->st_rects.deserialize(inbuffer + offset);
+        memcpy( &(this->rects[i]), &(this->st_rects), sizeof(opencv_apps::RotatedRect));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RotatedRectArray"; };
+    const char * getMD5(){ return "a27e397ed2b5b1a633561d324f64d2a6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RotatedRectArrayStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RotatedRectArrayStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_opencv_apps_RotatedRectArrayStamped_h
+#define _ROS_opencv_apps_RotatedRectArrayStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/RotatedRect.h"
+
+namespace opencv_apps
+{
+
+  class RotatedRectArrayStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t rects_length;
+      opencv_apps::RotatedRect st_rects;
+      opencv_apps::RotatedRect * rects;
+
+    RotatedRectArrayStamped():
+      header(),
+      rects_length(0), rects(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = rects_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->rects[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t rects_lengthT = *(inbuffer + offset++);
+      if(rects_lengthT > rects_length)
+        this->rects = (opencv_apps::RotatedRect*)realloc(this->rects, rects_lengthT * sizeof(opencv_apps::RotatedRect));
+      offset += 3;
+      rects_length = rects_lengthT;
+      for( uint8_t i = 0; i < rects_length; i++){
+      offset += this->st_rects.deserialize(inbuffer + offset);
+        memcpy( &(this->rects[i]), &(this->st_rects), sizeof(opencv_apps::RotatedRect));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RotatedRectArrayStamped"; };
+    const char * getMD5(){ return "89a2d4a7db2d2945ca46c25a3bd8c7c5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/RotatedRectStamped.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/RotatedRectStamped.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_opencv_apps_RotatedRectStamped_h
+#define _ROS_opencv_apps_RotatedRectStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "opencv_apps/RotatedRect.h"
+
+namespace opencv_apps
+{
+
+  class RotatedRectStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      opencv_apps::RotatedRect rect;
+
+    RotatedRectStamped():
+      header(),
+      rect()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->rect.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->rect.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/RotatedRectStamped"; };
+    const char * getMD5(){ return "ba2d76a1968e4f77570c01223781fe15"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 opencv_apps/Size.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/opencv_apps/Size.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_opencv_apps_Size_h
+#define _ROS_opencv_apps_Size_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace opencv_apps
+{
+
+  class Size : public ros::Msg
+  {
+    public:
+      double width;
+      double height;
+
+    Size():
+      width(0),
+      height(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_width.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_width.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_width.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_width.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_height.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_height.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_height.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_height.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->height);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_width.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      union {
+        double real;
+        uint64_t base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_height.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+     return offset;
+    }
+
+    const char * getType(){ return "opencv_apps/Size"; };
+    const char * getMD5(){ return "f86522e647336fb10b55359fe003f673"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 pcl_msgs/ModelCoefficients.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/ModelCoefficients.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_pcl_msgs_ModelCoefficients_h
+#define _ROS_pcl_msgs_ModelCoefficients_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace pcl_msgs
+{
+
+  class ModelCoefficients : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t values_length;
+      float st_values;
+      float * values;
+
+    ModelCoefficients():
+      header(),
+      values_length(0), values(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = values_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < values_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_valuesi;
+      u_valuesi.real = this->values[i];
+      *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t values_lengthT = *(inbuffer + offset++);
+      if(values_lengthT > values_length)
+        this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
+      offset += 3;
+      values_length = values_lengthT;
+      for( uint8_t i = 0; i < values_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_values;
+      u_st_values.base = 0;
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_values = u_st_values.real;
+      offset += sizeof(this->st_values);
+        memcpy( &(this->values[i]), &(this->st_values), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "pcl_msgs/ModelCoefficients"; };
+    const char * getMD5(){ return "ca27dea75e72cb894cd36f9e5005e93e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 pcl_msgs/PointIndices.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/PointIndices.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_pcl_msgs_PointIndices_h
+#define _ROS_pcl_msgs_PointIndices_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace pcl_msgs
+{
+
+  class PointIndices : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t indices_length;
+      int32_t st_indices;
+      int32_t * indices;
+
+    PointIndices():
+      header(),
+      indices_length(0), indices(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = indices_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < indices_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_indicesi;
+      u_indicesi.real = this->indices[i];
+      *(outbuffer + offset + 0) = (u_indicesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_indicesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_indicesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_indicesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->indices[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t indices_lengthT = *(inbuffer + offset++);
+      if(indices_lengthT > indices_length)
+        this->indices = (int32_t*)realloc(this->indices, indices_lengthT * sizeof(int32_t));
+      offset += 3;
+      indices_length = indices_lengthT;
+      for( uint8_t i = 0; i < indices_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_indices;
+      u_st_indices.base = 0;
+      u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_indices = u_st_indices.real;
+      offset += sizeof(this->st_indices);
+        memcpy( &(this->indices[i]), &(this->st_indices), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "pcl_msgs/PointIndices"; };
+    const char * getMD5(){ return "458c7998b7eaf99908256472e273b3d4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 pcl_msgs/PolygonMesh.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/PolygonMesh.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_pcl_msgs_PolygonMesh_h
+#define _ROS_pcl_msgs_PolygonMesh_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/PointCloud2.h"
+#include "pcl_msgs/Vertices.h"
+
+namespace pcl_msgs
+{
+
+  class PolygonMesh : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      sensor_msgs::PointCloud2 cloud;
+      uint8_t polygons_length;
+      pcl_msgs::Vertices st_polygons;
+      pcl_msgs::Vertices * polygons;
+
+    PolygonMesh():
+      header(),
+      cloud(),
+      polygons_length(0), polygons(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->cloud.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = polygons_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < polygons_length; i++){
+      offset += this->polygons[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->cloud.deserialize(inbuffer + offset);
+      uint8_t polygons_lengthT = *(inbuffer + offset++);
+      if(polygons_lengthT > polygons_length)
+        this->polygons = (pcl_msgs::Vertices*)realloc(this->polygons, polygons_lengthT * sizeof(pcl_msgs::Vertices));
+      offset += 3;
+      polygons_length = polygons_lengthT;
+      for( uint8_t i = 0; i < polygons_length; i++){
+      offset += this->st_polygons.deserialize(inbuffer + offset);
+        memcpy( &(this->polygons[i]), &(this->st_polygons), sizeof(pcl_msgs::Vertices));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "pcl_msgs/PolygonMesh"; };
+    const char * getMD5(){ return "45a5fc6ad2cde8489600a790acc9a38a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 pcl_msgs/Vertices.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/Vertices.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,66 @@
+#ifndef _ROS_pcl_msgs_Vertices_h
+#define _ROS_pcl_msgs_Vertices_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace pcl_msgs
+{
+
+  class Vertices : public ros::Msg
+  {
+    public:
+      uint8_t vertices_length;
+      uint32_t st_vertices;
+      uint32_t * vertices;
+
+    Vertices():
+      vertices_length(0), vertices(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = vertices_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < vertices_length; i++){
+      *(outbuffer + offset + 0) = (this->vertices[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->vertices[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->vertices[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->vertices[i] >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->vertices[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t vertices_lengthT = *(inbuffer + offset++);
+      if(vertices_lengthT > vertices_length)
+        this->vertices = (uint32_t*)realloc(this->vertices, vertices_lengthT * sizeof(uint32_t));
+      offset += 3;
+      vertices_length = vertices_lengthT;
+      for( uint8_t i = 0; i < vertices_length; i++){
+      this->st_vertices =  ((uint32_t) (*(inbuffer + offset)));
+      this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->st_vertices);
+        memcpy( &(this->vertices[i]), &(this->st_vertices), sizeof(uint32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "pcl_msgs/Vertices"; };
+    const char * getMD5(){ return "39bd7b1c23763ddd1b882b97cb7cfe11"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 polled_camera/GetPolledImage.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/polled_camera/GetPolledImage.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,194 @@
+#ifndef _ROS_SERVICE_GetPolledImage_h
+#define _ROS_SERVICE_GetPolledImage_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/RegionOfInterest.h"
+#include "ros/duration.h"
+#include "ros/time.h"
+
+namespace polled_camera
+{
+
+static const char GETPOLLEDIMAGE[] = "polled_camera/GetPolledImage";
+
+  class GetPolledImageRequest : public ros::Msg
+  {
+    public:
+      const char* response_namespace;
+      ros::Duration timeout;
+      uint32_t binning_x;
+      uint32_t binning_y;
+      sensor_msgs::RegionOfInterest roi;
+
+    GetPolledImageRequest():
+      response_namespace(""),
+      timeout(),
+      binning_x(0),
+      binning_y(0),
+      roi()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_response_namespace = strlen(this->response_namespace);
+      memcpy(outbuffer + offset, &length_response_namespace, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->response_namespace, length_response_namespace);
+      offset += length_response_namespace;
+      *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timeout.sec);
+      *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timeout.nsec);
+      *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_x);
+      *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_y);
+      offset += this->roi.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_response_namespace;
+      memcpy(&length_response_namespace, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_response_namespace; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_response_namespace-1]=0;
+      this->response_namespace = (char *)(inbuffer + offset-1);
+      offset += length_response_namespace;
+      this->timeout.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timeout.sec);
+      this->timeout.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timeout.nsec);
+      this->binning_x =  ((uint32_t) (*(inbuffer + offset)));
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->binning_x);
+      this->binning_y =  ((uint32_t) (*(inbuffer + offset)));
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->binning_y);
+      offset += this->roi.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return GETPOLLEDIMAGE; };
+    const char * getMD5(){ return "c77ed43e530fd48e9e7a2a93845e154c"; };
+
+  };
+
+  class GetPolledImageResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+      ros::Time stamp;
+
+    GetPolledImageResponse():
+      success(0),
+      status_message(""),
+      stamp()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.sec);
+      *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+      this->stamp.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.sec);
+      this->stamp.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return GETPOLLEDIMAGE; };
+    const char * getMD5(){ return "dbf1f851bc511800e6129ccd5a3542ab"; };
+
+  };
+
+  class GetPolledImage {
+    public:
+    typedef GetPolledImageRequest Request;
+    typedef GetPolledImageResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,46 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_H_
+#define _ROS_H_
+
+#include "ros/node_handle.h"
+#include "MbedHardware.h"
+
+namespace ros
+{
+  typedef NodeHandle_<MbedHardware> NodeHandle;
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/duration.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/duration.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,68 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_DURATION_H_
+#define _ROS_DURATION_H_
+
+#include <math.h>
+#include <stdint.h>
+
+namespace ros {
+
+  void normalizeSecNSecSigned(int32_t& sec, int32_t& nsec);
+
+  class Duration
+  {
+    public:
+      int32_t sec, nsec;
+
+      Duration() : sec(0), nsec(0) {}
+      Duration(int32_t _sec, int32_t _nsec) : sec(_sec), nsec(_nsec)
+      {
+        normalizeSecNSecSigned(sec, nsec);
+      }
+
+      double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); }
+      double toSec() const { return (double)sec + 1e-9*(double)nsec; };
+      void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); };
+
+      Duration& operator+=(const Duration &rhs);
+      Duration& operator-=(const Duration &rhs);
+      Duration& operator*=(double scale);
+  };
+
+}
+
+#endif
+
diff -r 000000000000 -r fd24f7ca9688 ros/msg.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/msg.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,129 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_MSG_H_
+#define _ROS_MSG_H_
+
+#include <stdint.h>
+
+namespace ros {
+
+/* Base Message Type */
+class Msg
+{
+public:
+  virtual int serialize(unsigned char *outbuffer) const = 0;
+  virtual int deserialize(unsigned char *data) = 0;
+  virtual const char * getType() = 0;
+  virtual const char * getMD5() = 0;
+
+  /**
+   * @brief This tricky function handles promoting a 32bit float to a 64bit
+   *        double, so that AVR can publish messages containing float64
+   *        fields, despite AVV having no native support for double.
+   *
+   * @param[out] outbuffer pointer for buffer to serialize to.
+   * @param[in] f value to serialize.
+   *
+   * @return number of bytes to advance the buffer pointer.
+   *
+   */
+  static int serializeAvrFloat64(unsigned char* outbuffer, const float f)
+  {
+    const int32_t* val = (int32_t*) &f;
+    int32_t exp = ((*val >> 23) & 255);
+    if (exp != 0)
+    {
+      exp += 1023 - 127;
+    }
+
+    int32_t sig = *val;
+    *(outbuffer++) = 0;
+    *(outbuffer++) = 0;
+    *(outbuffer++) = 0;
+    *(outbuffer++) = (sig << 5) & 0xff;
+    *(outbuffer++) = (sig >> 3) & 0xff;
+    *(outbuffer++) = (sig >> 11) & 0xff;
+    *(outbuffer++) = ((exp << 4) & 0xF0) | ((sig >> 19) & 0x0F);
+    *(outbuffer++) = (exp >> 4) & 0x7F;
+
+    // Mark negative bit as necessary.
+    if (f < 0)
+    {
+      *(outbuffer - 1) |= 0x80;
+    }
+
+    return 8;
+  }
+
+  /**
+   * @brief This tricky function handles demoting a 64bit double to a
+   *        32bit float, so that AVR can understand messages containing
+   *        float64 fields, despite AVR having no native support for double.
+   *
+   * @param[in] inbuffer pointer for buffer to deserialize from.
+   * @param[out] f pointer to place the deserialized value in.
+   *
+   * @return number of bytes to advance the buffer pointer.
+   */
+  static int deserializeAvrFloat64(const unsigned char* inbuffer, float* f)
+  {
+    uint32_t* val = (uint32_t*)f;
+    inbuffer += 3;
+
+    // Copy truncated mantissa.
+    *val = ((uint32_t)(*(inbuffer++)) >> 5 & 0x07);
+    *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 3;
+    *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 11;
+    *val |= ((uint32_t)(*inbuffer) & 0x0f) << 19;
+
+    // Copy truncated exponent.
+    uint32_t exp = ((uint32_t)(*(inbuffer++)) & 0xf0)>>4;
+    exp |= ((uint32_t)(*inbuffer) & 0x7f) << 4;
+    if (exp != 0)
+    {
+      *val |= ((exp) - 1023 + 127) << 23;
+    }  
+
+    // Copy negative sign.
+    *val |= ((uint32_t)(*(inbuffer++)) & 0x80) << 24;
+
+    return 8;
+  }
+
+};
+
+}  // namespace ros
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/node_handle.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/node_handle.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,543 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_NODE_HANDLE_H_
+#define ROS_NODE_HANDLE_H_
+
+#include <stdint.h>
+
+#include "std_msgs/Time.h"
+#include "rosserial_msgs/TopicInfo.h"
+#include "rosserial_msgs/Log.h"
+#include "rosserial_msgs/RequestParam.h"
+
+#define SYNC_SECONDS        5
+
+#define MODE_FIRST_FF       0
+/*
+ * The second sync byte is a protocol version. It's value is 0xff for the first
+ * version of the rosserial protocol (used up to hydro), 0xfe for the second version
+ * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable
+ * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy
+ * rosserial_arduino. It must be changed in both this file and in
+ * rosserial_python/src/rosserial_python/SerialClient.py
+ */
+#define MODE_PROTOCOL_VER   1
+#define PROTOCOL_VER1		0xff // through groovy
+#define PROTOCOL_VER2		0xfe // in hydro
+#define PROTOCOL_VER 		PROTOCOL_VER2
+#define MODE_SIZE_L         2
+#define MODE_SIZE_H         3
+#define MODE_SIZE_CHECKSUM  4   // checksum for msg size received from size L and H
+#define MODE_TOPIC_L        5   // waiting for topic id
+#define MODE_TOPIC_H        6
+#define MODE_MESSAGE        7
+#define MODE_MSG_CHECKSUM   8   // checksum for msg and topic id
+
+
+#define MSG_TIMEOUT 20  //20 milliseconds to recieve all of message data
+
+#include "msg.h"
+
+namespace ros {
+
+  class NodeHandleBase_{
+    public:
+      virtual int publish(int id, const Msg* msg)=0;
+      virtual int spinOnce()=0;
+      virtual bool connected()=0;
+    };
+}
+
+#include "publisher.h"
+#include "subscriber.h"
+#include "service_server.h"
+#include "service_client.h"
+
+namespace ros {
+
+  using rosserial_msgs::TopicInfo;
+
+  /* Node Handle */
+  template<class Hardware,
+           int MAX_SUBSCRIBERS=25,
+           int MAX_PUBLISHERS=25,
+           int INPUT_SIZE=512,
+           int OUTPUT_SIZE=512>
+  class NodeHandle_ : public NodeHandleBase_
+  {
+    protected:
+      Hardware hardware_;
+
+      /* time used for syncing */
+      uint32_t rt_time;
+
+      /* used for computing current time */
+      uint32_t sec_offset, nsec_offset;
+
+      uint8_t message_in[INPUT_SIZE];
+      uint8_t message_out[OUTPUT_SIZE];
+
+      Publisher * publishers[MAX_PUBLISHERS];
+      Subscriber_ * subscribers[MAX_SUBSCRIBERS];
+
+      /*
+       * Setup Functions
+       */
+    public:
+      NodeHandle_() : configured_(false) {
+
+        for(unsigned int i=0; i< MAX_PUBLISHERS; i++)
+	   publishers[i] = 0;
+
+        for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++)
+	   subscribers[i] = 0;
+
+        for(unsigned int i=0; i< INPUT_SIZE; i++)
+	   message_in[i] = 0;
+
+        for(unsigned int i=0; i< OUTPUT_SIZE; i++)
+	   message_out[i] = 0;
+
+        req_param_resp.ints_length = 0;
+        req_param_resp.ints = NULL;
+        req_param_resp.floats_length = 0;
+        req_param_resp.floats = NULL;
+        req_param_resp.ints_length = 0;
+        req_param_resp.ints = NULL;
+      }
+
+      Hardware* getHardware(){
+        return &hardware_;
+      }
+
+      /* Start serial, initialize buffers */
+      void initNode(){
+        hardware_.init();
+        mode_ = 0;
+        bytes_ = 0;
+        index_ = 0;
+        topic_ = 0;
+      };
+
+      /* Start a named port, which may be network server IP, initialize buffers */
+      void initNode(char *portName){
+        hardware_.init(portName);
+        mode_ = 0;
+        bytes_ = 0;
+        index_ = 0;
+        topic_ = 0;
+      };
+
+    protected:
+      //State machine variables for spinOnce
+      int mode_;
+      int bytes_;
+      int topic_;
+      int index_;
+      int checksum_;
+
+      bool configured_;
+
+      /* used for syncing the time */
+      uint32_t last_sync_time;
+      uint32_t last_sync_receive_time;
+      uint32_t last_msg_timeout_time;
+
+    public:
+      /* This function goes in your loop() function, it handles
+       *  serial input and callbacks for subscribers.
+       */
+
+
+      virtual int spinOnce(){
+
+        /* restart if timed out */
+        uint32_t c_time = hardware_.time();
+        if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
+            configured_ = false;
+         }
+
+        /* reset if message has timed out */
+        if ( mode_ != MODE_FIRST_FF){
+          if (c_time > last_msg_timeout_time){
+            mode_ = MODE_FIRST_FF;
+          }
+        }
+
+        /* while available buffer, read data */
+        while( true )
+        {
+          int data = hardware_.read();
+          if( data < 0 )
+            break;
+          checksum_ += data;
+          if( mode_ == MODE_MESSAGE ){        /* message data being recieved */
+            message_in[index_++] = data;
+            bytes_--;
+            if(bytes_ == 0)                  /* is message complete? if so, checksum */
+              mode_ = MODE_MSG_CHECKSUM;
+          }else if( mode_ == MODE_FIRST_FF ){
+            if(data == 0xff){
+              mode_++;
+              last_msg_timeout_time = c_time + MSG_TIMEOUT;
+            }
+            else if( hardware_.time() - c_time > (SYNC_SECONDS)){
+              /* We have been stuck in spinOnce too long, return error */
+              configured_=false;
+              return -2;
+            }
+          }else if( mode_ == MODE_PROTOCOL_VER ){
+            if(data == PROTOCOL_VER){
+              mode_++;
+            }else{
+              mode_ = MODE_FIRST_FF;
+              if (configured_ == false)
+                  requestSyncTime(); 	/* send a msg back showing our protocol version */
+            }
+	  }else if( mode_ == MODE_SIZE_L ){   /* bottom half of message size */
+            bytes_ = data;
+            index_ = 0;
+            mode_++;
+            checksum_ = data;               /* first byte for calculating size checksum */
+          }else if( mode_ == MODE_SIZE_H ){   /* top half of message size */
+            bytes_ += data<<8;
+	    mode_++;
+          }else if( mode_ == MODE_SIZE_CHECKSUM ){
+            if( (checksum_%256) == 255)
+	      mode_++;
+	    else
+	      mode_ = MODE_FIRST_FF;          /* Abandon the frame if the msg len is wrong */
+	  }else if( mode_ == MODE_TOPIC_L ){  /* bottom half of topic id */
+            topic_ = data;
+            mode_++;
+            checksum_ = data;               /* first byte included in checksum */
+          }else if( mode_ == MODE_TOPIC_H ){  /* top half of topic id */
+            topic_ += data<<8;
+            mode_ = MODE_MESSAGE;
+            if(bytes_ == 0)
+              mode_ = MODE_MSG_CHECKSUM;
+          }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */
+            mode_ = MODE_FIRST_FF;
+            if( (checksum_%256) == 255){
+              if(topic_ == TopicInfo::ID_PUBLISHER){
+                requestSyncTime();
+                negotiateTopics();
+                last_sync_time = c_time;
+                last_sync_receive_time = c_time;
+                return -1;
+              }else if(topic_ == TopicInfo::ID_TIME){
+                syncTime(message_in);
+              }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){
+                  req_param_resp.deserialize(message_in);
+                  param_recieved= true;
+              }else if(topic_ == TopicInfo::ID_TX_STOP){
+                  configured_ = false;
+              }else{
+                if(subscribers[topic_-100])
+                  subscribers[topic_-100]->callback( message_in );
+              }
+            }
+          }
+        }
+
+        /* occasionally sync time */
+        if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){
+          requestSyncTime();
+          last_sync_time = c_time;
+        }
+
+        return 0;
+      }
+
+
+      /* Are we connected to the PC? */
+      virtual bool connected() {
+        return configured_;
+      };
+
+      /********************************************************************
+       * Time functions
+       */
+
+      void requestSyncTime()
+      {
+        std_msgs::Time t;
+        publish(TopicInfo::ID_TIME, &t);
+        rt_time = hardware_.time();
+      }
+
+      void syncTime(uint8_t * data)
+      {
+        std_msgs::Time t;
+        uint32_t offset = hardware_.time() - rt_time;
+
+        t.deserialize(data);
+        t.data.sec += offset/1000;
+        t.data.nsec += (offset%1000)*1000000UL;
+
+        this->setNow(t.data);
+        last_sync_receive_time = hardware_.time();
+      }
+
+      Time now()
+      {
+        uint32_t ms = hardware_.time();
+        Time current_time;
+        current_time.sec = ms/1000 + sec_offset;
+        current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
+        normalizeSecNSec(current_time.sec, current_time.nsec);
+        return current_time;
+      }
+
+      void setNow( Time & new_now )
+      {
+        uint32_t ms = hardware_.time();
+        sec_offset = new_now.sec - ms/1000 - 1;
+        nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
+        normalizeSecNSec(sec_offset, nsec_offset);
+      }
+
+      /********************************************************************
+       * Topic Management
+       */
+
+      /* Register a new publisher */
+      bool advertise(Publisher & p)
+      {
+        for(int i = 0; i < MAX_PUBLISHERS; i++){
+          if(publishers[i] == 0){ // empty slot
+            publishers[i] = &p;
+            p.id_ = i+100+MAX_SUBSCRIBERS;
+            p.nh_ = this;
+            return true;
+          }
+        }
+        return false;
+      }
+
+      /* Register a new subscriber */
+      template<typename MsgT>
+      bool subscribe(Subscriber< MsgT> & s){
+        for(int i = 0; i < MAX_SUBSCRIBERS; i++){
+          if(subscribers[i] == 0){ // empty slot
+            subscribers[i] = (Subscriber_*) &s;
+            s.id_ = i+100;
+            return true;
+          }
+        }
+        return false;
+      }
+
+      /* Register a new Service Server */
+      template<typename MReq, typename MRes>
+      bool advertiseService(ServiceServer<MReq,MRes>& srv){
+        bool v = advertise(srv.pub);
+        for(int i = 0; i < MAX_SUBSCRIBERS; i++){
+          if(subscribers[i] == 0){ // empty slot
+            subscribers[i] = (Subscriber_*) &srv;
+            srv.id_ = i+100;
+            return v;
+          }
+        }
+        return false;
+      }
+
+      /* Register a new Service Client */
+      template<typename MReq, typename MRes>
+      bool serviceClient(ServiceClient<MReq, MRes>& srv){
+        bool v = advertise(srv.pub);
+        for(int i = 0; i < MAX_SUBSCRIBERS; i++){
+          if(subscribers[i] == 0){ // empty slot
+            subscribers[i] = (Subscriber_*) &srv;
+            srv.id_ = i+100;
+            return v;
+          }
+        }
+        return false;
+      }
+
+      void negotiateTopics()
+      {
+        rosserial_msgs::TopicInfo ti;
+        int i;
+        for(i = 0; i < MAX_PUBLISHERS; i++)
+        {
+          if(publishers[i] != 0) // non-empty slot
+          {
+            ti.topic_id = publishers[i]->id_;
+            ti.topic_name = (char *) publishers[i]->topic_;
+            ti.message_type = (char *) publishers[i]->msg_->getType();
+            ti.md5sum = (char *) publishers[i]->msg_->getMD5();
+            ti.buffer_size = OUTPUT_SIZE;
+            publish( publishers[i]->getEndpointType(), &ti );
+          }
+        }
+        for(i = 0; i < MAX_SUBSCRIBERS; i++)
+        {
+          if(subscribers[i] != 0) // non-empty slot
+          {
+            ti.topic_id = subscribers[i]->id_;
+            ti.topic_name = (char *) subscribers[i]->topic_;
+            ti.message_type = (char *) subscribers[i]->getMsgType();
+            ti.md5sum = (char *) subscribers[i]->getMsgMD5();
+            ti.buffer_size = INPUT_SIZE;
+            publish( subscribers[i]->getEndpointType(), &ti );
+          }
+        }
+        configured_ = true;
+      }
+
+      virtual int publish(int id, const Msg * msg)
+      {
+        if(id >= 100 && !configured_)
+	  return 0;
+
+        /* serialize message */
+        uint16_t l = msg->serialize(message_out+7);
+
+        /* setup the header */
+        message_out[0] = 0xff;
+        message_out[1] = PROTOCOL_VER;
+        message_out[2] = (uint8_t) ((uint16_t)l&255);
+        message_out[3] = (uint8_t) ((uint16_t)l>>8);
+	message_out[4] = 255 - ((message_out[2] + message_out[3])%256);
+        message_out[5] = (uint8_t) ((int16_t)id&255);
+        message_out[6] = (uint8_t) ((int16_t)id>>8);
+
+        /* calculate checksum */
+        int chk = 0;
+        for(int i =5; i<l+7; i++)
+          chk += message_out[i];
+        l += 7;
+        message_out[l++] = 255 - (chk%256);
+
+        if( l <= OUTPUT_SIZE ){
+          hardware_.write(message_out, l);
+          return l;
+        }else{
+          logerror("Message from device dropped: message larger than buffer.");
+          return -1;
+        }
+      }
+
+      /********************************************************************
+       * Logging
+       */
+
+    private:
+      void log(char byte, const char * msg){
+        rosserial_msgs::Log l;
+        l.level= byte;
+        l.msg = (char*)msg;
+        publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
+      }
+
+    public:
+      void logdebug(const char* msg){
+        log(rosserial_msgs::Log::ROSDEBUG, msg);
+      }
+      void loginfo(const char * msg){
+        log(rosserial_msgs::Log::INFO, msg);
+      }
+      void logwarn(const char *msg){
+        log(rosserial_msgs::Log::WARN, msg);
+      }
+      void logerror(const char*msg){
+        log(rosserial_msgs::Log::ERROR, msg);
+      }
+      void logfatal(const char*msg){
+        log(rosserial_msgs::Log::FATAL, msg);
+      }
+
+      /********************************************************************
+       * Parameters
+       */
+
+    private:
+      bool param_recieved;
+      rosserial_msgs::RequestParamResponse req_param_resp;
+
+      bool requestParam(const char * name, int time_out =  1000){
+        param_recieved = false;
+        rosserial_msgs::RequestParamRequest req;
+        req.name  = (char*)name;
+        publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
+        uint16_t end_time = hardware_.time() + time_out;
+        while(!param_recieved ){
+          spinOnce();
+          if (hardware_.time() > end_time) return false;
+        }
+        return true;
+      }
+
+    public:
+      bool getParam(const char* name, int* param, int length =1){
+        if (requestParam(name) ){
+          if (length == req_param_resp.ints_length){
+            //copy it over
+            for(int i=0; i<length; i++)
+              param[i] = req_param_resp.ints[i];
+            return true;
+          }
+        }
+        return false;
+      }
+      bool getParam(const char* name, float* param, int length=1){
+        if (requestParam(name) ){
+          if (length == req_param_resp.floats_length){
+            //copy it over
+            for(int i=0; i<length; i++)
+              param[i] = req_param_resp.floats[i];
+            return true;
+          }
+        }
+        return false;
+      }
+      bool getParam(const char* name, char** param, int length=1){
+        if (requestParam(name) ){
+          if (length == req_param_resp.strings_length){
+            //copy it over
+            for(int i=0; i<length; i++)
+              strcpy(param[i],req_param_resp.strings[i]);
+            return true;
+          }
+        }
+        return false;
+      }
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/publisher.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/publisher.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,67 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_PUBLISHER_H_
+#define _ROS_PUBLISHER_H_
+
+#include "rosserial_msgs/TopicInfo.h"
+#include "node_handle.h"
+
+namespace ros {
+
+  /* Generic Publisher */
+  class Publisher
+  {
+    public:
+      Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) :
+        topic_(topic_name), 
+        msg_(msg),
+        endpoint_(endpoint) {};
+
+      int publish( const Msg * msg ) { return nh_->publish(id_, msg); };
+      int getEndpointType(){ return endpoint_; }
+
+      const char * topic_;
+      Msg *msg_;
+      // id_ and no_ are set by NodeHandle when we advertise 
+      int id_;
+      NodeHandleBase_* nh_;
+
+    private:
+      int endpoint_;
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/service_client.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_client.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,83 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_SERVICE_CLIENT_H_
+#define _ROS_SERVICE_CLIENT_H_
+
+#include "rosserial_msgs/TopicInfo.h"
+
+#include "publisher.h"
+#include "subscriber.h"
+
+namespace ros {
+
+  template<typename MReq , typename MRes>
+  class ServiceClient : public Subscriber_  {
+    public:
+      ServiceClient(const char* topic_name) : 
+        pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER)
+      {
+        this->topic_ = topic_name;
+        this->waiting = true;
+      }
+
+      virtual void call(const MReq & request, MRes & response)
+      {
+        if(!pub.nh_->connected()) return;
+        ret = &response;
+        waiting = true;
+        pub.publish(&request);
+        while(waiting && pub.nh_->connected())
+          if(pub.nh_->spinOnce() < 0) break;
+      }
+
+      // these refer to the subscriber
+      virtual void callback(unsigned char *data){
+        ret->deserialize(data);
+        waiting = false;
+      }
+      virtual const char * getMsgType(){ return this->resp.getType(); }
+      virtual const char * getMsgMD5(){ return this->resp.getMD5(); }
+      virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; }
+
+      MReq req;
+      MRes resp;
+      MRes * ret;
+      bool waiting;
+      Publisher pub;
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/service_server.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_server.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,76 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_SERVICE_SERVER_H_
+#define _ROS_SERVICE_SERVER_H_
+
+#include "rosserial_msgs/TopicInfo.h"
+
+#include "publisher.h"
+#include "subscriber.h"
+
+namespace ros {
+
+  template<typename MReq , typename MRes>
+  class ServiceServer : public Subscriber_ {
+    public:
+      typedef void(*CallbackT)(const MReq&,  MRes&);
+
+      ServiceServer(const char* topic_name, CallbackT cb) :
+        pub(topic_name, &resp, rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_PUBLISHER)
+      {
+        this->topic_ = topic_name;
+        this->cb_ = cb;
+      }
+
+      // these refer to the subscriber
+      virtual void callback(unsigned char *data){
+        req.deserialize(data);
+        cb_(req,resp);
+        pub.publish(&resp);
+      }
+      virtual const char * getMsgType(){ return this->req.getType(); }
+      virtual const char * getMsgMD5(){ return this->req.getMD5(); }
+      virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; }
+
+      MReq req;
+      MRes resp;
+      Publisher pub;
+    private:
+      CallbackT cb_;
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/subscriber.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/subscriber.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,88 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_SUBSCRIBER_H_
+#define ROS_SUBSCRIBER_H_
+
+#include "rosserial_msgs/TopicInfo.h"
+
+namespace ros {
+
+  /* Base class for objects subscribers. */
+  class Subscriber_
+  {
+    public:
+      virtual void callback(unsigned char *data)=0;
+      virtual int getEndpointType()=0;
+
+      // id_ is set by NodeHandle when we advertise 
+      int id_;
+
+      virtual const char * getMsgType()=0;
+      virtual const char * getMsgMD5()=0;
+      const char * topic_;
+  };
+
+
+  /* Actual subscriber, templated on message type. */
+  template<typename MsgT>
+  class Subscriber: public Subscriber_{
+    public:
+      typedef void(*CallbackT)(const MsgT&);
+      MsgT msg;
+
+      Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
+        cb_(cb),
+        endpoint_(endpoint)
+      {
+        topic_ = topic_name;
+      };
+
+      virtual void callback(unsigned char* data){
+        msg.deserialize(data);
+        this->cb_(msg);
+      }
+
+      virtual const char * getMsgType(){ return this->msg.getType(); }
+      virtual const char * getMsgMD5(){ return this->msg.getMD5(); }
+      virtual int getEndpointType(){ return endpoint_; }
+
+    private:
+      CallbackT cb_;
+      int endpoint_;
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 ros/time.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/time.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,74 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_TIME_H_
+#define ROS_TIME_H_
+
+#include <math.h>
+#include <stdint.h>
+
+#include "ros/duration.h"
+
+namespace ros
+{
+  void normalizeSecNSec(uint32_t &sec, uint32_t &nsec);
+
+  class Time
+  {
+    public:
+      uint32_t sec, nsec;
+
+      Time() : sec(0), nsec(0) {}
+      Time(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
+      {
+        normalizeSecNSec(sec, nsec);
+      }
+
+      double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); }
+      double toSec() const { return (double)sec + 1e-9*(double)nsec; };
+      void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); };
+
+      uint32_t toNsec() { return (uint32_t)sec*1000000000ull + (uint32_t)nsec; };
+      Time& fromNSec(int32_t t);
+
+      Time& operator +=(const Duration &rhs);
+      Time& operator -=(const Duration &rhs);
+
+      static Time now();
+      static void setNow( Time & new_now);
+  };
+
+}
+
+#endif
diff -r 000000000000 -r fd24f7ca9688 roscpp/Empty.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Empty.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_SERVICE_Empty_h
+#define _ROS_SERVICE_Empty_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+static const char EMPTY[] = "roscpp/Empty";
+
+  class EmptyRequest : public ros::Msg
+  {
+    public:
+
+    EmptyRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return EMPTY; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class EmptyResponse : public ros::Msg
+  {
+    public:
+
+    EmptyResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return EMPTY; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class Empty {
+    public:
+    typedef EmptyRequest Request;
+    typedef EmptyResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 roscpp/GetLoggers.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/GetLoggers.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,91 @@
+#ifndef _ROS_SERVICE_GetLoggers_h
+#define _ROS_SERVICE_GetLoggers_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "roscpp/Logger.h"
+
+namespace roscpp
+{
+
+static const char GETLOGGERS[] = "roscpp/GetLoggers";
+
+  class GetLoggersRequest : public ros::Msg
+  {
+    public:
+
+    GetLoggersRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETLOGGERS; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetLoggersResponse : public ros::Msg
+  {
+    public:
+      uint8_t loggers_length;
+      roscpp::Logger st_loggers;
+      roscpp::Logger * loggers;
+
+    GetLoggersResponse():
+      loggers_length(0), loggers(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = loggers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < loggers_length; i++){
+      offset += this->loggers[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t loggers_lengthT = *(inbuffer + offset++);
+      if(loggers_lengthT > loggers_length)
+        this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger));
+      offset += 3;
+      loggers_length = loggers_lengthT;
+      for( uint8_t i = 0; i < loggers_length; i++){
+      offset += this->st_loggers.deserialize(inbuffer + offset);
+        memcpy( &(this->loggers[i]), &(this->st_loggers), sizeof(roscpp::Logger));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return GETLOGGERS; };
+    const char * getMD5(){ return "32e97e85527d4678a8f9279894bb64b0"; };
+
+  };
+
+  class GetLoggers {
+    public:
+    typedef GetLoggersRequest Request;
+    typedef GetLoggersResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 roscpp/Logger.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Logger.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_roscpp_Logger_h
+#define _ROS_roscpp_Logger_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+  class Logger : public ros::Msg
+  {
+    public:
+      const char* name;
+      const char* level;
+
+    Logger():
+      name(""),
+      level("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_level = strlen(this->level);
+      memcpy(outbuffer + offset, &length_level, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->level, length_level);
+      offset += length_level;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_level;
+      memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_level; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_level-1]=0;
+      this->level = (char *)(inbuffer + offset-1);
+      offset += length_level;
+     return offset;
+    }
+
+    const char * getType(){ return "roscpp/Logger"; };
+    const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 roscpp/SetLoggerLevel.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/SetLoggerLevel.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_SetLoggerLevel_h
+#define _ROS_SERVICE_SetLoggerLevel_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+static const char SETLOGGERLEVEL[] = "roscpp/SetLoggerLevel";
+
+  class SetLoggerLevelRequest : public ros::Msg
+  {
+    public:
+      const char* logger;
+      const char* level;
+
+    SetLoggerLevelRequest():
+      logger(""),
+      level("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_logger = strlen(this->logger);
+      memcpy(outbuffer + offset, &length_logger, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->logger, length_logger);
+      offset += length_logger;
+      uint32_t length_level = strlen(this->level);
+      memcpy(outbuffer + offset, &length_level, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->level, length_level);
+      offset += length_level;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_logger;
+      memcpy(&length_logger, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_logger; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_logger-1]=0;
+      this->logger = (char *)(inbuffer + offset-1);
+      offset += length_logger;
+      uint32_t length_level;
+      memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_level; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_level-1]=0;
+      this->level = (char *)(inbuffer + offset-1);
+      offset += length_level;
+     return offset;
+    }
+
+    const char * getType(){ return SETLOGGERLEVEL; };
+    const char * getMD5(){ return "51da076440d78ca1684d36c868df61ea"; };
+
+  };
+
+  class SetLoggerLevelResponse : public ros::Msg
+  {
+    public:
+
+    SetLoggerLevelResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SETLOGGERLEVEL; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SetLoggerLevel {
+    public:
+    typedef SetLoggerLevelRequest Request;
+    typedef SetLoggerLevelResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 roscpp_tutorials/TwoInts.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp_tutorials/TwoInts.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,163 @@
+#ifndef _ROS_SERVICE_TwoInts_h
+#define _ROS_SERVICE_TwoInts_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp_tutorials
+{
+
+static const char TWOINTS[] = "roscpp_tutorials/TwoInts";
+
+  class TwoIntsRequest : public ros::Msg
+  {
+    public:
+      int64_t a;
+      int64_t b;
+
+    TwoIntsRequest():
+      a(0),
+      b(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->b);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+     return offset;
+    }
+
+    const char * getType(){ return TWOINTS; };
+    const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; };
+
+  };
+
+  class TwoIntsResponse : public ros::Msg
+  {
+    public:
+      int64_t sum;
+
+    TwoIntsResponse():
+      sum(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.real = this->sum;
+      *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sum);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.base = 0;
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sum = u_sum.real;
+      offset += sizeof(this->sum);
+     return offset;
+    }
+
+    const char * getType(){ return TWOINTS; };
+    const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; };
+
+  };
+
+  class TwoInts {
+    public:
+    typedef TwoIntsRequest Request;
+    typedef TwoIntsResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rosgraph_msgs/Clock.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Clock.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_rosgraph_msgs_Clock_h
+#define _ROS_rosgraph_msgs_Clock_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace rosgraph_msgs
+{
+
+  class Clock : public ros::Msg
+  {
+    public:
+      ros::Time clock;
+
+    Clock():
+      clock()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->clock.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->clock.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->clock.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->clock.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->clock.sec);
+      *(outbuffer + offset + 0) = (this->clock.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->clock.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->clock.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->clock.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->clock.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->clock.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->clock.sec);
+      this->clock.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->clock.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "rosgraph_msgs/Clock"; };
+    const char * getMD5(){ return "a9c97c1d230cfc112e270351a944ee47"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rosgraph_msgs/Log.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Log.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,173 @@
+#ifndef _ROS_rosgraph_msgs_Log_h
+#define _ROS_rosgraph_msgs_Log_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace rosgraph_msgs
+{
+
+  class Log : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      int8_t level;
+      const char* name;
+      const char* msg;
+      const char* file;
+      const char* function;
+      uint32_t line;
+      uint8_t topics_length;
+      char* st_topics;
+      char* * topics;
+      enum { DEBUG = 1  };
+      enum { INFO = 2   };
+      enum { WARN = 4   };
+      enum { ERROR = 8  };
+      enum { FATAL = 16  };
+
+    Log():
+      header(),
+      level(0),
+      name(""),
+      msg(""),
+      file(""),
+      function(""),
+      line(0),
+      topics_length(0), topics(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_level;
+      u_level.real = this->level;
+      *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->level);
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_msg = strlen(this->msg);
+      memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->msg, length_msg);
+      offset += length_msg;
+      uint32_t length_file = strlen(this->file);
+      memcpy(outbuffer + offset, &length_file, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->file, length_file);
+      offset += length_file;
+      uint32_t length_function = strlen(this->function);
+      memcpy(outbuffer + offset, &length_function, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->function, length_function);
+      offset += length_function;
+      *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->line);
+      *(outbuffer + offset++) = topics_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], length_topicsi);
+      offset += length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_level;
+      u_level.base = 0;
+      u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->level = u_level.real;
+      offset += sizeof(this->level);
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_msg;
+      memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_msg; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_msg-1]=0;
+      this->msg = (char *)(inbuffer + offset-1);
+      offset += length_msg;
+      uint32_t length_file;
+      memcpy(&length_file, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_file; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_file-1]=0;
+      this->file = (char *)(inbuffer + offset-1);
+      offset += length_file;
+      uint32_t length_function;
+      memcpy(&length_function, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_function; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_function-1]=0;
+      this->function = (char *)(inbuffer + offset-1);
+      offset += length_function;
+      this->line =  ((uint32_t) (*(inbuffer + offset)));
+      this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->line);
+      uint8_t topics_lengthT = *(inbuffer + offset++);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      offset += 3;
+      topics_length = topics_lengthT;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_topics; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_topics-1]=0;
+      this->st_topics = (char *)(inbuffer + offset-1);
+      offset += length_st_topics;
+        memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "rosgraph_msgs/Log"; };
+    const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rosgraph_msgs/TopicStatistics.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/TopicStatistics.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,333 @@
+#ifndef _ROS_rosgraph_msgs_TopicStatistics_h
+#define _ROS_rosgraph_msgs_TopicStatistics_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+#include "ros/duration.h"
+
+namespace rosgraph_msgs
+{
+
+  class TopicStatistics : public ros::Msg
+  {
+    public:
+      const char* topic;
+      const char* node_pub;
+      const char* node_sub;
+      ros::Time window_start;
+      ros::Time window_stop;
+      int32_t delivered_msgs;
+      int32_t dropped_msgs;
+      int32_t traffic;
+      ros::Duration period_mean;
+      ros::Duration period_stddev;
+      ros::Duration period_max;
+      ros::Duration stamp_age_mean;
+      ros::Duration stamp_age_stddev;
+      ros::Duration stamp_age_max;
+
+    TopicStatistics():
+      topic(""),
+      node_pub(""),
+      node_sub(""),
+      window_start(),
+      window_stop(),
+      delivered_msgs(0),
+      dropped_msgs(0),
+      traffic(0),
+      period_mean(),
+      period_stddev(),
+      period_max(),
+      stamp_age_mean(),
+      stamp_age_stddev(),
+      stamp_age_max()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      uint32_t length_node_pub = strlen(this->node_pub);
+      memcpy(outbuffer + offset, &length_node_pub, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->node_pub, length_node_pub);
+      offset += length_node_pub;
+      uint32_t length_node_sub = strlen(this->node_sub);
+      memcpy(outbuffer + offset, &length_node_sub, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->node_sub, length_node_sub);
+      offset += length_node_sub;
+      *(outbuffer + offset + 0) = (this->window_start.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->window_start.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->window_start.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->window_start.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->window_start.sec);
+      *(outbuffer + offset + 0) = (this->window_start.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->window_start.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->window_start.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->window_start.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->window_start.nsec);
+      *(outbuffer + offset + 0) = (this->window_stop.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->window_stop.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->window_stop.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->window_stop.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->window_stop.sec);
+      *(outbuffer + offset + 0) = (this->window_stop.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->window_stop.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->window_stop.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->window_stop.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->window_stop.nsec);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_delivered_msgs;
+      u_delivered_msgs.real = this->delivered_msgs;
+      *(outbuffer + offset + 0) = (u_delivered_msgs.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_delivered_msgs.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_delivered_msgs.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_delivered_msgs.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delivered_msgs);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_dropped_msgs;
+      u_dropped_msgs.real = this->dropped_msgs;
+      *(outbuffer + offset + 0) = (u_dropped_msgs.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_dropped_msgs.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_dropped_msgs.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_dropped_msgs.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->dropped_msgs);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_traffic;
+      u_traffic.real = this->traffic;
+      *(outbuffer + offset + 0) = (u_traffic.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_traffic.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_traffic.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_traffic.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->traffic);
+      *(outbuffer + offset + 0) = (this->period_mean.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_mean.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_mean.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_mean.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_mean.sec);
+      *(outbuffer + offset + 0) = (this->period_mean.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_mean.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_mean.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_mean.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_mean.nsec);
+      *(outbuffer + offset + 0) = (this->period_stddev.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_stddev.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_stddev.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_stddev.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_stddev.sec);
+      *(outbuffer + offset + 0) = (this->period_stddev.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_stddev.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_stddev.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_stddev.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_stddev.nsec);
+      *(outbuffer + offset + 0) = (this->period_max.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_max.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_max.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_max.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_max.sec);
+      *(outbuffer + offset + 0) = (this->period_max.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->period_max.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->period_max.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->period_max.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->period_max.nsec);
+      *(outbuffer + offset + 0) = (this->stamp_age_mean.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_mean.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_mean.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_mean.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_mean.sec);
+      *(outbuffer + offset + 0) = (this->stamp_age_mean.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_mean.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_mean.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_mean.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_mean.nsec);
+      *(outbuffer + offset + 0) = (this->stamp_age_stddev.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_stddev.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_stddev.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_stddev.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_stddev.sec);
+      *(outbuffer + offset + 0) = (this->stamp_age_stddev.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_stddev.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_stddev.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_stddev.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_stddev.nsec);
+      *(outbuffer + offset + 0) = (this->stamp_age_max.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_max.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_max.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_max.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_max.sec);
+      *(outbuffer + offset + 0) = (this->stamp_age_max.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp_age_max.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp_age_max.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp_age_max.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp_age_max.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+      uint32_t length_node_pub;
+      memcpy(&length_node_pub, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_node_pub; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_node_pub-1]=0;
+      this->node_pub = (char *)(inbuffer + offset-1);
+      offset += length_node_pub;
+      uint32_t length_node_sub;
+      memcpy(&length_node_sub, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_node_sub; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_node_sub-1]=0;
+      this->node_sub = (char *)(inbuffer + offset-1);
+      offset += length_node_sub;
+      this->window_start.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->window_start.sec);
+      this->window_start.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->window_start.nsec);
+      this->window_stop.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->window_stop.sec);
+      this->window_stop.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->window_stop.nsec);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_delivered_msgs;
+      u_delivered_msgs.base = 0;
+      u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->delivered_msgs = u_delivered_msgs.real;
+      offset += sizeof(this->delivered_msgs);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_dropped_msgs;
+      u_dropped_msgs.base = 0;
+      u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->dropped_msgs = u_dropped_msgs.real;
+      offset += sizeof(this->dropped_msgs);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_traffic;
+      u_traffic.base = 0;
+      u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->traffic = u_traffic.real;
+      offset += sizeof(this->traffic);
+      this->period_mean.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_mean.sec);
+      this->period_mean.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_mean.nsec);
+      this->period_stddev.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_stddev.sec);
+      this->period_stddev.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_stddev.nsec);
+      this->period_max.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_max.sec);
+      this->period_max.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->period_max.nsec);
+      this->stamp_age_mean.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_mean.sec);
+      this->stamp_age_mean.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_mean.nsec);
+      this->stamp_age_stddev.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_stddev.sec);
+      this->stamp_age_stddev.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_stddev.nsec);
+      this->stamp_age_max.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_max.sec);
+      this->stamp_age_max.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp_age_max.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "rosgraph_msgs/TopicStatistics"; };
+    const char * getMD5(){ return "10152ed868c5097a5e2e4a89d7daa710"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rospy_tutorials/AddTwoInts.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/AddTwoInts.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,163 @@
+#ifndef _ROS_SERVICE_AddTwoInts_h
+#define _ROS_SERVICE_AddTwoInts_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rospy_tutorials
+{
+
+static const char ADDTWOINTS[] = "rospy_tutorials/AddTwoInts";
+
+  class AddTwoIntsRequest : public ros::Msg
+  {
+    public:
+      int64_t a;
+      int64_t b;
+
+    AddTwoIntsRequest():
+      a(0),
+      b(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->b);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+     return offset;
+    }
+
+    const char * getType(){ return ADDTWOINTS; };
+    const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; };
+
+  };
+
+  class AddTwoIntsResponse : public ros::Msg
+  {
+    public:
+      int64_t sum;
+
+    AddTwoIntsResponse():
+      sum(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.real = this->sum;
+      *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->sum);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_sum;
+      u_sum.base = 0;
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->sum = u_sum.real;
+      offset += sizeof(this->sum);
+     return offset;
+    }
+
+    const char * getType(){ return ADDTWOINTS; };
+    const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; };
+
+  };
+
+  class AddTwoInts {
+    public:
+    typedef AddTwoIntsRequest Request;
+    typedef AddTwoIntsResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rospy_tutorials/BadTwoInts.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/BadTwoInts.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,147 @@
+#ifndef _ROS_SERVICE_BadTwoInts_h
+#define _ROS_SERVICE_BadTwoInts_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rospy_tutorials
+{
+
+static const char BADTWOINTS[] = "rospy_tutorials/BadTwoInts";
+
+  class BadTwoIntsRequest : public ros::Msg
+  {
+    public:
+      int64_t a;
+      int32_t b;
+
+    BadTwoIntsRequest():
+      a(0),
+      b(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->a);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->b);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+     return offset;
+    }
+
+    const char * getType(){ return BADTWOINTS; };
+    const char * getMD5(){ return "29bb5c7dea8bf822f53e94b0ee5a3a56"; };
+
+  };
+
+  class BadTwoIntsResponse : public ros::Msg
+  {
+    public:
+      int32_t sum;
+
+    BadTwoIntsResponse():
+      sum(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sum;
+      u_sum.real = this->sum;
+      *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sum);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_sum;
+      u_sum.base = 0;
+      u_sum.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sum.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sum.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sum.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->sum = u_sum.real;
+      offset += sizeof(this->sum);
+     return offset;
+    }
+
+    const char * getType(){ return BADTWOINTS; };
+    const char * getMD5(){ return "0ba699c25c9418c0366f3595c0c8e8ec"; };
+
+  };
+
+  class BadTwoInts {
+    public:
+    typedef BadTwoIntsRequest Request;
+    typedef BadTwoIntsResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rospy_tutorials/Floats.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/Floats.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_rospy_tutorials_Floats_h
+#define _ROS_rospy_tutorials_Floats_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rospy_tutorials
+{
+
+  class Floats : public ros::Msg
+  {
+    public:
+      uint8_t data_length;
+      float st_data;
+      float * data;
+
+    Floats():
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "rospy_tutorials/Floats"; };
+    const char * getMD5(){ return "420cd38b6b071cd49f2970c3e2cee511"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rospy_tutorials/HeaderString.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/HeaderString.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_rospy_tutorials_HeaderString_h
+#define _ROS_rospy_tutorials_HeaderString_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace rospy_tutorials
+{
+
+  class HeaderString : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* data;
+
+    HeaderString():
+      header(),
+      data("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_data = strlen(this->data);
+      memcpy(outbuffer + offset, &length_data, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->data, length_data);
+      offset += length_data;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_data;
+      memcpy(&length_data, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_data-1]=0;
+      this->data = (char *)(inbuffer + offset-1);
+      offset += length_data;
+     return offset;
+    }
+
+    const char * getType(){ return "rospy_tutorials/HeaderString"; };
+    const char * getMD5(){ return "c99a9440709e4d4a9716d55b8270d5e7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rosserial_mbed/Adc.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_mbed/Adc.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_rosserial_mbed_Adc_h
+#define _ROS_rosserial_mbed_Adc_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_mbed
+{
+
+  class Adc : public ros::Msg
+  {
+    public:
+      uint16_t adc0;
+      uint16_t adc1;
+      uint16_t adc2;
+      uint16_t adc3;
+      uint16_t adc4;
+      uint16_t adc5;
+
+    Adc():
+      adc0(0),
+      adc1(0),
+      adc2(0),
+      adc3(0),
+      adc4(0),
+      adc5(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->adc0 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc0 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc0);
+      *(outbuffer + offset + 0) = (this->adc1 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc1 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc1);
+      *(outbuffer + offset + 0) = (this->adc2 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc2 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc2);
+      *(outbuffer + offset + 0) = (this->adc3 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc3 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc3);
+      *(outbuffer + offset + 0) = (this->adc4 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc4 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc4);
+      *(outbuffer + offset + 0) = (this->adc5 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc5 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc5);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->adc0 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc0);
+      this->adc1 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc1);
+      this->adc2 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc2);
+      this->adc3 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc3);
+      this->adc4 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc4);
+      this->adc5 =  ((uint16_t) (*(inbuffer + offset)));
+      this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc5);
+     return offset;
+    }
+
+    const char * getType(){ return "rosserial_mbed/Adc"; };
+    const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rosserial_mbed/Test.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_mbed/Test.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_Test_h
+#define _ROS_SERVICE_Test_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_mbed
+{
+
+static const char TEST[] = "rosserial_mbed/Test";
+
+  class TestRequest : public ros::Msg
+  {
+    public:
+      const char* input;
+
+    TestRequest():
+      input("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_input = strlen(this->input);
+      memcpy(outbuffer + offset, &length_input, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->input, length_input);
+      offset += length_input;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_input;
+      memcpy(&length_input, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_input; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_input-1]=0;
+      this->input = (char *)(inbuffer + offset-1);
+      offset += length_input;
+     return offset;
+    }
+
+    const char * getType(){ return TEST; };
+    const char * getMD5(){ return "39e92f1778057359c64c7b8a7d7b19de"; };
+
+  };
+
+  class TestResponse : public ros::Msg
+  {
+    public:
+      const char* output;
+
+    TestResponse():
+      output("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_output = strlen(this->output);
+      memcpy(outbuffer + offset, &length_output, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->output, length_output);
+      offset += length_output;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_output;
+      memcpy(&length_output, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_output; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_output-1]=0;
+      this->output = (char *)(inbuffer + offset-1);
+      offset += length_output;
+     return offset;
+    }
+
+    const char * getType(){ return TEST; };
+    const char * getMD5(){ return "0825d95fdfa2c8f4bbb4e9c74bccd3fd"; };
+
+  };
+
+  class Test {
+    public:
+    typedef TestRequest Request;
+    typedef TestResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rosserial_msgs/Log.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/Log.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,65 @@
+#ifndef _ROS_rosserial_msgs_Log_h
+#define _ROS_rosserial_msgs_Log_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+  class Log : public ros::Msg
+  {
+    public:
+      uint8_t level;
+      const char* msg;
+      enum { ROSDEBUG = 0 };
+      enum { INFO = 1 };
+      enum { WARN = 2 };
+      enum { ERROR = 3 };
+      enum { FATAL = 4 };
+
+    Log():
+      level(0),
+      msg("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->level);
+      uint32_t length_msg = strlen(this->msg);
+      memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->msg, length_msg);
+      offset += length_msg;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->level =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->level);
+      uint32_t length_msg;
+      memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_msg; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_msg-1]=0;
+      this->msg = (char *)(inbuffer + offset-1);
+      offset += length_msg;
+     return offset;
+    }
+
+    const char * getType(){ return "rosserial_msgs/Log"; };
+    const char * getMD5(){ return "11abd731c25933261cd6183bd12d6295"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 rosserial_msgs/RequestMessageInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestMessageInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,118 @@
+#ifndef _ROS_SERVICE_RequestMessageInfo_h
+#define _ROS_SERVICE_RequestMessageInfo_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+static const char REQUESTMESSAGEINFO[] = "rosserial_msgs/RequestMessageInfo";
+
+  class RequestMessageInfoRequest : public ros::Msg
+  {
+    public:
+      const char* type;
+
+    RequestMessageInfoRequest():
+      type("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_type = strlen(this->type);
+      memcpy(outbuffer + offset, &length_type, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_type;
+      memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_type-1]=0;
+      this->type = (char *)(inbuffer + offset-1);
+      offset += length_type;
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTMESSAGEINFO; };
+    const char * getMD5(){ return "dc67331de85cf97091b7d45e5c64ab75"; };
+
+  };
+
+  class RequestMessageInfoResponse : public ros::Msg
+  {
+    public:
+      const char* md5;
+      const char* definition;
+
+    RequestMessageInfoResponse():
+      md5(""),
+      definition("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_md5 = strlen(this->md5);
+      memcpy(outbuffer + offset, &length_md5, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->md5, length_md5);
+      offset += length_md5;
+      uint32_t length_definition = strlen(this->definition);
+      memcpy(outbuffer + offset, &length_definition, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->definition, length_definition);
+      offset += length_definition;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_md5;
+      memcpy(&length_md5, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_md5; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_md5-1]=0;
+      this->md5 = (char *)(inbuffer + offset-1);
+      offset += length_md5;
+      uint32_t length_definition;
+      memcpy(&length_definition, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_definition; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_definition-1]=0;
+      this->definition = (char *)(inbuffer + offset-1);
+      offset += length_definition;
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTMESSAGEINFO; };
+    const char * getMD5(){ return "fe452186a069bed40f09b8628fe5eac8"; };
+
+  };
+
+  class RequestMessageInfo {
+    public:
+    typedef RequestMessageInfoRequest Request;
+    typedef RequestMessageInfoResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rosserial_msgs/RequestParam.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestParam.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,196 @@
+#ifndef _ROS_SERVICE_RequestParam_h
+#define _ROS_SERVICE_RequestParam_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam";
+
+  class RequestParamRequest : public ros::Msg
+  {
+    public:
+      const char* name;
+
+    RequestParamRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTPARAM; };
+    const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
+
+  };
+
+  class RequestParamResponse : public ros::Msg
+  {
+    public:
+      uint8_t ints_length;
+      int32_t st_ints;
+      int32_t * ints;
+      uint8_t floats_length;
+      float st_floats;
+      float * floats;
+      uint8_t strings_length;
+      char* st_strings;
+      char* * strings;
+
+    RequestParamResponse():
+      ints_length(0), ints(NULL),
+      floats_length(0), floats(NULL),
+      strings_length(0), strings(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = ints_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < ints_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_intsi;
+      u_intsi.real = this->ints[i];
+      *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ints[i]);
+      }
+      *(outbuffer + offset++) = floats_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < floats_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_floatsi;
+      u_floatsi.real = this->floats[i];
+      *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->floats[i]);
+      }
+      *(outbuffer + offset++) = strings_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < strings_length; i++){
+      uint32_t length_stringsi = strlen(this->strings[i]);
+      memcpy(outbuffer + offset, &length_stringsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->strings[i], length_stringsi);
+      offset += length_stringsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t ints_lengthT = *(inbuffer + offset++);
+      if(ints_lengthT > ints_length)
+        this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t));
+      offset += 3;
+      ints_length = ints_lengthT;
+      for( uint8_t i = 0; i < ints_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_ints;
+      u_st_ints.base = 0;
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_ints = u_st_ints.real;
+      offset += sizeof(this->st_ints);
+        memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t));
+      }
+      uint8_t floats_lengthT = *(inbuffer + offset++);
+      if(floats_lengthT > floats_length)
+        this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
+      offset += 3;
+      floats_length = floats_lengthT;
+      for( uint8_t i = 0; i < floats_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_floats;
+      u_st_floats.base = 0;
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_floats = u_st_floats.real;
+      offset += sizeof(this->st_floats);
+        memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float));
+      }
+      uint8_t strings_lengthT = *(inbuffer + offset++);
+      if(strings_lengthT > strings_length)
+        this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
+      offset += 3;
+      strings_length = strings_lengthT;
+      for( uint8_t i = 0; i < strings_length; i++){
+      uint32_t length_st_strings;
+      memcpy(&length_st_strings, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_strings; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_strings-1]=0;
+      this->st_strings = (char *)(inbuffer + offset-1);
+      offset += length_st_strings;
+        memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTPARAM; };
+    const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; };
+
+  };
+
+  class RequestParam {
+    public:
+    typedef RequestParamRequest Request;
+    typedef RequestParamResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rosserial_msgs/RequestServiceInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestServiceInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,134 @@
+#ifndef _ROS_SERVICE_RequestServiceInfo_h
+#define _ROS_SERVICE_RequestServiceInfo_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+static const char REQUESTSERVICEINFO[] = "rosserial_msgs/RequestServiceInfo";
+
+  class RequestServiceInfoRequest : public ros::Msg
+  {
+    public:
+      const char* service;
+
+    RequestServiceInfoRequest():
+      service("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_service = strlen(this->service);
+      memcpy(outbuffer + offset, &length_service, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->service, length_service);
+      offset += length_service;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_service;
+      memcpy(&length_service, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_service; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_service-1]=0;
+      this->service = (char *)(inbuffer + offset-1);
+      offset += length_service;
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTSERVICEINFO; };
+    const char * getMD5(){ return "1cbcfa13b08f6d36710b9af8741e6112"; };
+
+  };
+
+  class RequestServiceInfoResponse : public ros::Msg
+  {
+    public:
+      const char* service_md5;
+      const char* request_md5;
+      const char* response_md5;
+
+    RequestServiceInfoResponse():
+      service_md5(""),
+      request_md5(""),
+      response_md5("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_service_md5 = strlen(this->service_md5);
+      memcpy(outbuffer + offset, &length_service_md5, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->service_md5, length_service_md5);
+      offset += length_service_md5;
+      uint32_t length_request_md5 = strlen(this->request_md5);
+      memcpy(outbuffer + offset, &length_request_md5, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->request_md5, length_request_md5);
+      offset += length_request_md5;
+      uint32_t length_response_md5 = strlen(this->response_md5);
+      memcpy(outbuffer + offset, &length_response_md5, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->response_md5, length_response_md5);
+      offset += length_response_md5;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_service_md5;
+      memcpy(&length_service_md5, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_service_md5; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_service_md5-1]=0;
+      this->service_md5 = (char *)(inbuffer + offset-1);
+      offset += length_service_md5;
+      uint32_t length_request_md5;
+      memcpy(&length_request_md5, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_request_md5; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_request_md5-1]=0;
+      this->request_md5 = (char *)(inbuffer + offset-1);
+      offset += length_request_md5;
+      uint32_t length_response_md5;
+      memcpy(&length_response_md5, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_response_md5; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_response_md5-1]=0;
+      this->response_md5 = (char *)(inbuffer + offset-1);
+      offset += length_response_md5;
+     return offset;
+    }
+
+    const char * getType(){ return REQUESTSERVICEINFO; };
+    const char * getMD5(){ return "c3d6dd25b909596479fbbc6559fa6874"; };
+
+  };
+
+  class RequestServiceInfo {
+    public:
+    typedef RequestServiceInfoRequest Request;
+    typedef RequestServiceInfoResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 rosserial_msgs/TopicInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/TopicInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,125 @@
+#ifndef _ROS_rosserial_msgs_TopicInfo_h
+#define _ROS_rosserial_msgs_TopicInfo_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+  class TopicInfo : public ros::Msg
+  {
+    public:
+      uint16_t topic_id;
+      const char* topic_name;
+      const char* message_type;
+      const char* md5sum;
+      int32_t buffer_size;
+      enum { ID_PUBLISHER = 0 };
+      enum { ID_SUBSCRIBER = 1 };
+      enum { ID_SERVICE_SERVER = 2 };
+      enum { ID_SERVICE_CLIENT = 4 };
+      enum { ID_PARAMETER_REQUEST = 6 };
+      enum { ID_LOG = 7 };
+      enum { ID_TIME = 10 };
+      enum { ID_TX_STOP = 11 };
+
+    TopicInfo():
+      topic_id(0),
+      topic_name(""),
+      message_type(""),
+      md5sum(""),
+      buffer_size(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->topic_id);
+      uint32_t length_topic_name = strlen(this->topic_name);
+      memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic_name, length_topic_name);
+      offset += length_topic_name;
+      uint32_t length_message_type = strlen(this->message_type);
+      memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->message_type, length_message_type);
+      offset += length_message_type;
+      uint32_t length_md5sum = strlen(this->md5sum);
+      memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->md5sum, length_md5sum);
+      offset += length_md5sum;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_buffer_size;
+      u_buffer_size.real = this->buffer_size;
+      *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->buffer_size);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->topic_id =  ((uint16_t) (*(inbuffer + offset)));
+      this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->topic_id);
+      uint32_t length_topic_name;
+      memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic_name-1]=0;
+      this->topic_name = (char *)(inbuffer + offset-1);
+      offset += length_topic_name;
+      uint32_t length_message_type;
+      memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_message_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_message_type-1]=0;
+      this->message_type = (char *)(inbuffer + offset-1);
+      offset += length_message_type;
+      uint32_t length_md5sum;
+      memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_md5sum; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_md5sum-1]=0;
+      this->md5sum = (char *)(inbuffer + offset-1);
+      offset += length_md5sum;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_buffer_size;
+      u_buffer_size.base = 0;
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->buffer_size = u_buffer_size.real;
+      offset += sizeof(this->buffer_size);
+     return offset;
+    }
+
+    const char * getType(){ return "rosserial_msgs/TopicInfo"; };
+    const char * getMD5(){ return "0ad51f88fc44892f8c10684077646005"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/CameraInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CameraInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,264 @@
+#ifndef _ROS_sensor_msgs_CameraInfo_h
+#define _ROS_sensor_msgs_CameraInfo_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/RegionOfInterest.h"
+
+namespace sensor_msgs
+{
+
+  class CameraInfo : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint32_t height;
+      uint32_t width;
+      const char* distortion_model;
+      uint8_t D_length;
+      double st_D;
+      double * D;
+      double K[9];
+      double R[9];
+      double P[12];
+      uint32_t binning_x;
+      uint32_t binning_y;
+      sensor_msgs::RegionOfInterest roi;
+
+    CameraInfo():
+      header(),
+      height(0),
+      width(0),
+      distortion_model(""),
+      D_length(0), D(NULL),
+      K(),
+      R(),
+      P(),
+      binning_x(0),
+      binning_y(0),
+      roi()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      uint32_t length_distortion_model = strlen(this->distortion_model);
+      memcpy(outbuffer + offset, &length_distortion_model, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->distortion_model, length_distortion_model);
+      offset += length_distortion_model;
+      *(outbuffer + offset++) = D_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < D_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Di;
+      u_Di.real = this->D[i];
+      *(outbuffer + offset + 0) = (u_Di.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_Di.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_Di.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_Di.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_Di.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_Di.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_Di.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_Di.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->D[i]);
+      }
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Ki;
+      u_Ki.real = this->K[i];
+      *(outbuffer + offset + 0) = (u_Ki.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_Ki.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_Ki.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_Ki.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_Ki.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_Ki.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_Ki.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_Ki.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->K[i]);
+      }
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Ri;
+      u_Ri.real = this->R[i];
+      *(outbuffer + offset + 0) = (u_Ri.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_Ri.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_Ri.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_Ri.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_Ri.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_Ri.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_Ri.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_Ri.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->R[i]);
+      }
+      for( uint8_t i = 0; i < 12; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Pi;
+      u_Pi.real = this->P[i];
+      *(outbuffer + offset + 0) = (u_Pi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_Pi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_Pi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_Pi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_Pi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_Pi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_Pi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_Pi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->P[i]);
+      }
+      *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_x);
+      *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_y);
+      offset += this->roi.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      uint32_t length_distortion_model;
+      memcpy(&length_distortion_model, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_distortion_model; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_distortion_model-1]=0;
+      this->distortion_model = (char *)(inbuffer + offset-1);
+      offset += length_distortion_model;
+      uint8_t D_lengthT = *(inbuffer + offset++);
+      if(D_lengthT > D_length)
+        this->D = (double*)realloc(this->D, D_lengthT * sizeof(double));
+      offset += 3;
+      D_length = D_lengthT;
+      for( uint8_t i = 0; i < D_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_D;
+      u_st_D.base = 0;
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_D.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_D = u_st_D.real;
+      offset += sizeof(this->st_D);
+        memcpy( &(this->D[i]), &(this->st_D), sizeof(double));
+      }
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Ki;
+      u_Ki.base = 0;
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_Ki.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->K[i] = u_Ki.real;
+      offset += sizeof(this->K[i]);
+      }
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Ri;
+      u_Ri.base = 0;
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_Ri.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->R[i] = u_Ri.real;
+      offset += sizeof(this->R[i]);
+      }
+      for( uint8_t i = 0; i < 12; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_Pi;
+      u_Pi.base = 0;
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_Pi.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->P[i] = u_Pi.real;
+      offset += sizeof(this->P[i]);
+      }
+      this->binning_x =  ((uint32_t) (*(inbuffer + offset)));
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->binning_x);
+      this->binning_y =  ((uint32_t) (*(inbuffer + offset)));
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->binning_y);
+      offset += this->roi.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/CameraInfo"; };
+    const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/ChannelFloat32.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/ChannelFloat32.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,93 @@
+#ifndef _ROS_sensor_msgs_ChannelFloat32_h
+#define _ROS_sensor_msgs_ChannelFloat32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class ChannelFloat32 : public ros::Msg
+  {
+    public:
+      const char* name;
+      uint8_t values_length;
+      float st_values;
+      float * values;
+
+    ChannelFloat32():
+      name(""),
+      values_length(0), values(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      *(outbuffer + offset++) = values_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < values_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_valuesi;
+      u_valuesi.real = this->values[i];
+      *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint8_t values_lengthT = *(inbuffer + offset++);
+      if(values_lengthT > values_length)
+        this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
+      offset += 3;
+      values_length = values_lengthT;
+      for( uint8_t i = 0; i < values_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_values;
+      u_st_values.base = 0;
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_values = u_st_values.real;
+      offset += sizeof(this->st_values);
+        memcpy( &(this->values[i]), &(this->st_values), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/ChannelFloat32"; };
+    const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/CompressedImage.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CompressedImage.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,81 @@
+#ifndef _ROS_sensor_msgs_CompressedImage_h
+#define _ROS_sensor_msgs_CompressedImage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class CompressedImage : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* format;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+
+    CompressedImage():
+      header(),
+      format(""),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_format = strlen(this->format);
+      memcpy(outbuffer + offset, &length_format, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->format, length_format);
+      offset += length_format;
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_format;
+      memcpy(&length_format, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_format; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_format-1]=0;
+      this->format = (char *)(inbuffer + offset-1);
+      offset += length_format;
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/CompressedImage"; };
+    const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/FluidPressure.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/FluidPressure.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,105 @@
+#ifndef _ROS_sensor_msgs_FluidPressure_h
+#define _ROS_sensor_msgs_FluidPressure_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class FluidPressure : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double fluid_pressure;
+      double variance;
+
+    FluidPressure():
+      header(),
+      fluid_pressure(0),
+      variance(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_fluid_pressure;
+      u_fluid_pressure.real = this->fluid_pressure;
+      *(outbuffer + offset + 0) = (u_fluid_pressure.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_fluid_pressure.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_fluid_pressure.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_fluid_pressure.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_fluid_pressure.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_fluid_pressure.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_fluid_pressure.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_fluid_pressure.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->fluid_pressure);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.real = this->variance;
+      *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->variance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_fluid_pressure;
+      u_fluid_pressure.base = 0;
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_fluid_pressure.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->fluid_pressure = u_fluid_pressure.real;
+      offset += sizeof(this->fluid_pressure);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.base = 0;
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->variance = u_variance.real;
+      offset += sizeof(this->variance);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/FluidPressure"; };
+    const char * getMD5(){ return "804dc5cea1c5306d6a2eb80b9833befe"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Illuminance.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Illuminance.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,105 @@
+#ifndef _ROS_sensor_msgs_Illuminance_h
+#define _ROS_sensor_msgs_Illuminance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Illuminance : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double illuminance;
+      double variance;
+
+    Illuminance():
+      header(),
+      illuminance(0),
+      variance(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_illuminance;
+      u_illuminance.real = this->illuminance;
+      *(outbuffer + offset + 0) = (u_illuminance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_illuminance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_illuminance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_illuminance.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_illuminance.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_illuminance.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_illuminance.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_illuminance.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->illuminance);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.real = this->variance;
+      *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->variance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_illuminance;
+      u_illuminance.base = 0;
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_illuminance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->illuminance = u_illuminance.real;
+      offset += sizeof(this->illuminance);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.base = 0;
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->variance = u_variance.real;
+      offset += sizeof(this->variance);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Illuminance"; };
+    const char * getMD5(){ return "8cf5febb0952fca9d650c3d11a81a188"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Image.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Image.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,123 @@
+#ifndef _ROS_sensor_msgs_Image_h
+#define _ROS_sensor_msgs_Image_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Image : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint32_t height;
+      uint32_t width;
+      const char* encoding;
+      uint8_t is_bigendian;
+      uint32_t step;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+
+    Image():
+      header(),
+      height(0),
+      width(0),
+      encoding(""),
+      is_bigendian(0),
+      step(0),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      uint32_t length_encoding = strlen(this->encoding);
+      memcpy(outbuffer + offset, &length_encoding, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->encoding, length_encoding);
+      offset += length_encoding;
+      *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_bigendian);
+      *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->step);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      uint32_t length_encoding;
+      memcpy(&length_encoding, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_encoding; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_encoding-1]=0;
+      this->encoding = (char *)(inbuffer + offset-1);
+      offset += length_encoding;
+      this->is_bigendian =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->is_bigendian);
+      this->step =  ((uint32_t) (*(inbuffer + offset)));
+      this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->step);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Image"; };
+    const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Imu.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Imu.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,162 @@
+#ifndef _ROS_sensor_msgs_Imu_h
+#define _ROS_sensor_msgs_Imu_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Quaternion.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace sensor_msgs
+{
+
+  class Imu : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Quaternion orientation;
+      double orientation_covariance[9];
+      geometry_msgs::Vector3 angular_velocity;
+      double angular_velocity_covariance[9];
+      geometry_msgs::Vector3 linear_acceleration;
+      double linear_acceleration_covariance[9];
+
+    Imu():
+      header(),
+      orientation(),
+      orientation_covariance(),
+      angular_velocity(),
+      angular_velocity_covariance(),
+      linear_acceleration(),
+      linear_acceleration_covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->orientation.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_orientation_covariancei;
+      u_orientation_covariancei.real = this->orientation_covariance[i];
+      *(outbuffer + offset + 0) = (u_orientation_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_orientation_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_orientation_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_orientation_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_orientation_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_orientation_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_orientation_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_orientation_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->orientation_covariance[i]);
+      }
+      offset += this->angular_velocity.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_angular_velocity_covariancei;
+      u_angular_velocity_covariancei.real = this->angular_velocity_covariance[i];
+      *(outbuffer + offset + 0) = (u_angular_velocity_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angular_velocity_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angular_velocity_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angular_velocity_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_angular_velocity_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_angular_velocity_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_angular_velocity_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_angular_velocity_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->angular_velocity_covariance[i]);
+      }
+      offset += this->linear_acceleration.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_linear_acceleration_covariancei;
+      u_linear_acceleration_covariancei.real = this->linear_acceleration_covariance[i];
+      *(outbuffer + offset + 0) = (u_linear_acceleration_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_linear_acceleration_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_linear_acceleration_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_linear_acceleration_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_linear_acceleration_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_linear_acceleration_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_linear_acceleration_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_linear_acceleration_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->linear_acceleration_covariance[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->orientation.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_orientation_covariancei;
+      u_orientation_covariancei.base = 0;
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->orientation_covariance[i] = u_orientation_covariancei.real;
+      offset += sizeof(this->orientation_covariance[i]);
+      }
+      offset += this->angular_velocity.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_angular_velocity_covariancei;
+      u_angular_velocity_covariancei.base = 0;
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->angular_velocity_covariance[i] = u_angular_velocity_covariancei.real;
+      offset += sizeof(this->angular_velocity_covariance[i]);
+      }
+      offset += this->linear_acceleration.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_linear_acceleration_covariancei;
+      u_linear_acceleration_covariancei.base = 0;
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->linear_acceleration_covariance[i] = u_linear_acceleration_covariancei.real;
+      offset += sizeof(this->linear_acceleration_covariance[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Imu"; };
+    const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/JointState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JointState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,216 @@
+#ifndef _ROS_sensor_msgs_JointState_h
+#define _ROS_sensor_msgs_JointState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class JointState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t name_length;
+      char* st_name;
+      char* * name;
+      uint8_t position_length;
+      double st_position;
+      double * position;
+      uint8_t velocity_length;
+      double st_velocity;
+      double * velocity;
+      uint8_t effort_length;
+      double st_effort;
+      double * effort;
+
+    JointState():
+      header(),
+      name_length(0), name(NULL),
+      position_length(0), position(NULL),
+      velocity_length(0), velocity(NULL),
+      effort_length(0), effort(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset++) = position_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_positioni;
+      u_positioni.real = this->position[i];
+      *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position[i]);
+      }
+      *(outbuffer + offset++) = velocity_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < velocity_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_velocityi;
+      u_velocityi.real = this->velocity[i];
+      *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->velocity[i]);
+      }
+      *(outbuffer + offset++) = effort_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < effort_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_efforti;
+      u_efforti.real = this->effort[i];
+      *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->effort[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      uint8_t position_lengthT = *(inbuffer + offset++);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      offset += 3;
+      position_length = position_lengthT;
+      for( uint8_t i = 0; i < position_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_position;
+      u_st_position.base = 0;
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_position = u_st_position.real;
+      offset += sizeof(this->st_position);
+        memcpy( &(this->position[i]), &(this->st_position), sizeof(double));
+      }
+      uint8_t velocity_lengthT = *(inbuffer + offset++);
+      if(velocity_lengthT > velocity_length)
+        this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
+      offset += 3;
+      velocity_length = velocity_lengthT;
+      for( uint8_t i = 0; i < velocity_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_velocity;
+      u_st_velocity.base = 0;
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_velocity = u_st_velocity.real;
+      offset += sizeof(this->st_velocity);
+        memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double));
+      }
+      uint8_t effort_lengthT = *(inbuffer + offset++);
+      if(effort_lengthT > effort_length)
+        this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
+      offset += 3;
+      effort_length = effort_lengthT;
+      for( uint8_t i = 0; i < effort_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_effort;
+      u_st_effort.base = 0;
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_effort = u_st_effort.real;
+      offset += sizeof(this->st_effort);
+        memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/JointState"; };
+    const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Joy.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Joy.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,121 @@
+#ifndef _ROS_sensor_msgs_Joy_h
+#define _ROS_sensor_msgs_Joy_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Joy : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t axes_length;
+      float st_axes;
+      float * axes;
+      uint8_t buttons_length;
+      int32_t st_buttons;
+      int32_t * buttons;
+
+    Joy():
+      header(),
+      axes_length(0), axes(NULL),
+      buttons_length(0), buttons(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = axes_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < axes_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_axesi;
+      u_axesi.real = this->axes[i];
+      *(outbuffer + offset + 0) = (u_axesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_axesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_axesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_axesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->axes[i]);
+      }
+      *(outbuffer + offset++) = buttons_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < buttons_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_buttonsi;
+      u_buttonsi.real = this->buttons[i];
+      *(outbuffer + offset + 0) = (u_buttonsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_buttonsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_buttonsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_buttonsi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->buttons[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t axes_lengthT = *(inbuffer + offset++);
+      if(axes_lengthT > axes_length)
+        this->axes = (float*)realloc(this->axes, axes_lengthT * sizeof(float));
+      offset += 3;
+      axes_length = axes_lengthT;
+      for( uint8_t i = 0; i < axes_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_axes;
+      u_st_axes.base = 0;
+      u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_axes = u_st_axes.real;
+      offset += sizeof(this->st_axes);
+        memcpy( &(this->axes[i]), &(this->st_axes), sizeof(float));
+      }
+      uint8_t buttons_lengthT = *(inbuffer + offset++);
+      if(buttons_lengthT > buttons_length)
+        this->buttons = (int32_t*)realloc(this->buttons, buttons_lengthT * sizeof(int32_t));
+      offset += 3;
+      buttons_length = buttons_lengthT;
+      for( uint8_t i = 0; i < buttons_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_buttons;
+      u_st_buttons.base = 0;
+      u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_buttons = u_st_buttons.real;
+      offset += sizeof(this->st_buttons);
+        memcpy( &(this->buttons[i]), &(this->st_buttons), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Joy"; };
+    const char * getMD5(){ return "5a9ea5f83505693b71e785041e67a8bb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/JoyFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JoyFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_sensor_msgs_JoyFeedback_h
+#define _ROS_sensor_msgs_JoyFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class JoyFeedback : public ros::Msg
+  {
+    public:
+      uint8_t type;
+      uint8_t id;
+      float intensity;
+      enum { TYPE_LED =  0 };
+      enum { TYPE_RUMBLE =  1 };
+      enum { TYPE_BUZZER =  2 };
+
+    JoyFeedback():
+      type(0),
+      id(0),
+      intensity(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->type);
+      *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->id);
+      union {
+        float real;
+        uint32_t base;
+      } u_intensity;
+      u_intensity.real = this->intensity;
+      *(outbuffer + offset + 0) = (u_intensity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_intensity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_intensity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_intensity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->intensity);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->type);
+      this->id =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->id);
+      union {
+        float real;
+        uint32_t base;
+      } u_intensity;
+      u_intensity.base = 0;
+      u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->intensity = u_intensity.real;
+      offset += sizeof(this->intensity);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/JoyFeedback"; };
+    const char * getMD5(){ return "f4dcd73460360d98f36e55ee7f2e46f1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/JoyFeedbackArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JoyFeedbackArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_sensor_msgs_JoyFeedbackArray_h
+#define _ROS_sensor_msgs_JoyFeedbackArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/JoyFeedback.h"
+
+namespace sensor_msgs
+{
+
+  class JoyFeedbackArray : public ros::Msg
+  {
+    public:
+      uint8_t array_length;
+      sensor_msgs::JoyFeedback st_array;
+      sensor_msgs::JoyFeedback * array;
+
+    JoyFeedbackArray():
+      array_length(0), array(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = array_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < array_length; i++){
+      offset += this->array[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t array_lengthT = *(inbuffer + offset++);
+      if(array_lengthT > array_length)
+        this->array = (sensor_msgs::JoyFeedback*)realloc(this->array, array_lengthT * sizeof(sensor_msgs::JoyFeedback));
+      offset += 3;
+      array_length = array_lengthT;
+      for( uint8_t i = 0; i < array_length; i++){
+      offset += this->st_array.deserialize(inbuffer + offset);
+        memcpy( &(this->array[i]), &(this->st_array), sizeof(sensor_msgs::JoyFeedback));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/JoyFeedbackArray"; };
+    const char * getMD5(){ return "cde5730a895b1fc4dee6f91b754b213d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/LaserEcho.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/LaserEcho.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,77 @@
+#ifndef _ROS_sensor_msgs_LaserEcho_h
+#define _ROS_sensor_msgs_LaserEcho_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class LaserEcho : public ros::Msg
+  {
+    public:
+      uint8_t echoes_length;
+      float st_echoes;
+      float * echoes;
+
+    LaserEcho():
+      echoes_length(0), echoes(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = echoes_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < echoes_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_echoesi;
+      u_echoesi.real = this->echoes[i];
+      *(outbuffer + offset + 0) = (u_echoesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_echoesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_echoesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_echoesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->echoes[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t echoes_lengthT = *(inbuffer + offset++);
+      if(echoes_lengthT > echoes_length)
+        this->echoes = (float*)realloc(this->echoes, echoes_lengthT * sizeof(float));
+      offset += 3;
+      echoes_length = echoes_lengthT;
+      for( uint8_t i = 0; i < echoes_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_echoes;
+      u_st_echoes.base = 0;
+      u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_echoes.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_echoes = u_st_echoes.real;
+      offset += sizeof(this->st_echoes);
+        memcpy( &(this->echoes[i]), &(this->st_echoes), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/LaserEcho"; };
+    const char * getMD5(){ return "8bc5ae449b200fba4d552b4225586696"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/LaserScan.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/LaserScan.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,282 @@
+#ifndef _ROS_sensor_msgs_LaserScan_h
+#define _ROS_sensor_msgs_LaserScan_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class LaserScan : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      float angle_min;
+      float angle_max;
+      float angle_increment;
+      float time_increment;
+      float scan_time;
+      float range_min;
+      float range_max;
+      uint8_t ranges_length;
+      float st_ranges;
+      float * ranges;
+      uint8_t intensities_length;
+      float st_intensities;
+      float * intensities;
+
+    LaserScan():
+      header(),
+      angle_min(0),
+      angle_max(0),
+      angle_increment(0),
+      time_increment(0),
+      scan_time(0),
+      range_min(0),
+      range_max(0),
+      ranges_length(0), ranges(NULL),
+      intensities_length(0), intensities(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_min;
+      u_angle_min.real = this->angle_min;
+      *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_max;
+      u_angle_max.real = this->angle_max;
+      *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_increment;
+      u_angle_increment.real = this->angle_increment;
+      *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_time_increment;
+      u_time_increment.real = this->time_increment;
+      *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_scan_time;
+      u_scan_time.real = this->scan_time;
+      *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_min;
+      u_range_min.real = this->range_min;
+      *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_max;
+      u_range_max.real = this->range_max;
+      *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_max);
+      *(outbuffer + offset++) = ranges_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < ranges_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_rangesi;
+      u_rangesi.real = this->ranges[i];
+      *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ranges[i]);
+      }
+      *(outbuffer + offset++) = intensities_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < intensities_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_intensitiesi;
+      u_intensitiesi.real = this->intensities[i];
+      *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->intensities[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_min;
+      u_angle_min.base = 0;
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_min = u_angle_min.real;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_max;
+      u_angle_max.base = 0;
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_max = u_angle_max.real;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_increment;
+      u_angle_increment.base = 0;
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_increment = u_angle_increment.real;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_time_increment;
+      u_time_increment.base = 0;
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->time_increment = u_time_increment.real;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_scan_time;
+      u_scan_time.base = 0;
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->scan_time = u_scan_time.real;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_min;
+      u_range_min.base = 0;
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_min = u_range_min.real;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_max;
+      u_range_max.base = 0;
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_max = u_range_max.real;
+      offset += sizeof(this->range_max);
+      uint8_t ranges_lengthT = *(inbuffer + offset++);
+      if(ranges_lengthT > ranges_length)
+        this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float));
+      offset += 3;
+      ranges_length = ranges_lengthT;
+      for( uint8_t i = 0; i < ranges_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_ranges;
+      u_st_ranges.base = 0;
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_ranges = u_st_ranges.real;
+      offset += sizeof(this->st_ranges);
+        memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float));
+      }
+      uint8_t intensities_lengthT = *(inbuffer + offset++);
+      if(intensities_lengthT > intensities_length)
+        this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float));
+      offset += 3;
+      intensities_length = intensities_lengthT;
+      for( uint8_t i = 0; i < intensities_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_intensities;
+      u_st_intensities.base = 0;
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_intensities = u_st_intensities.real;
+      offset += sizeof(this->st_intensities);
+        memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/LaserScan"; };
+    const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/MagneticField.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MagneticField.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,83 @@
+#ifndef _ROS_sensor_msgs_MagneticField_h
+#define _ROS_sensor_msgs_MagneticField_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace sensor_msgs
+{
+
+  class MagneticField : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Vector3 magnetic_field;
+      double magnetic_field_covariance[9];
+
+    MagneticField():
+      header(),
+      magnetic_field(),
+      magnetic_field_covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->magnetic_field.serialize(outbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_magnetic_field_covariancei;
+      u_magnetic_field_covariancei.real = this->magnetic_field_covariance[i];
+      *(outbuffer + offset + 0) = (u_magnetic_field_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_magnetic_field_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_magnetic_field_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_magnetic_field_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_magnetic_field_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_magnetic_field_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_magnetic_field_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_magnetic_field_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->magnetic_field_covariance[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->magnetic_field.deserialize(inbuffer + offset);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_magnetic_field_covariancei;
+      u_magnetic_field_covariancei.base = 0;
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_magnetic_field_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->magnetic_field_covariance[i] = u_magnetic_field_covariancei.real;
+      offset += sizeof(this->magnetic_field_covariance[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/MagneticField"; };
+    const char * getMD5(){ return "2f3b0b43eed0c9501de0fa3ff89a45aa"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/MultiDOFJointState.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MultiDOFJointState.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,138 @@
+#ifndef _ROS_sensor_msgs_MultiDOFJointState_h
+#define _ROS_sensor_msgs_MultiDOFJointState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Transform.h"
+#include "geometry_msgs/Twist.h"
+#include "geometry_msgs/Wrench.h"
+
+namespace sensor_msgs
+{
+
+  class MultiDOFJointState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      uint8_t transforms_length;
+      geometry_msgs::Transform st_transforms;
+      geometry_msgs::Transform * transforms;
+      uint8_t twist_length;
+      geometry_msgs::Twist st_twist;
+      geometry_msgs::Twist * twist;
+      uint8_t wrench_length;
+      geometry_msgs::Wrench st_wrench;
+      geometry_msgs::Wrench * wrench;
+
+    MultiDOFJointState():
+      header(),
+      joint_names_length(0), joint_names(NULL),
+      transforms_length(0), transforms(NULL),
+      twist_length(0), twist(NULL),
+      wrench_length(0), wrench(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset++) = transforms_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = twist_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = wrench_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < wrench_length; i++){
+      offset += this->wrench[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      uint8_t transforms_lengthT = *(inbuffer + offset++);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
+      offset += 3;
+      transforms_length = transforms_lengthT;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->st_transforms.deserialize(inbuffer + offset);
+        memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
+      }
+      uint8_t twist_lengthT = *(inbuffer + offset++);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      twist_length = twist_lengthT;
+      for( uint8_t i = 0; i < twist_length; i++){
+      offset += this->st_twist.deserialize(inbuffer + offset);
+        memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
+      }
+      uint8_t wrench_lengthT = *(inbuffer + offset++);
+      if(wrench_lengthT > wrench_length)
+        this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
+      offset += 3;
+      wrench_length = wrench_lengthT;
+      for( uint8_t i = 0; i < wrench_length; i++){
+      offset += this->st_wrench.deserialize(inbuffer + offset);
+        memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/MultiDOFJointState"; };
+    const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/MultiEchoLaserScan.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MultiEchoLaserScan.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,245 @@
+#ifndef _ROS_sensor_msgs_MultiEchoLaserScan_h
+#define _ROS_sensor_msgs_MultiEchoLaserScan_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/LaserEcho.h"
+
+namespace sensor_msgs
+{
+
+  class MultiEchoLaserScan : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      float angle_min;
+      float angle_max;
+      float angle_increment;
+      float time_increment;
+      float scan_time;
+      float range_min;
+      float range_max;
+      uint8_t ranges_length;
+      sensor_msgs::LaserEcho st_ranges;
+      sensor_msgs::LaserEcho * ranges;
+      uint8_t intensities_length;
+      sensor_msgs::LaserEcho st_intensities;
+      sensor_msgs::LaserEcho * intensities;
+
+    MultiEchoLaserScan():
+      header(),
+      angle_min(0),
+      angle_max(0),
+      angle_increment(0),
+      time_increment(0),
+      scan_time(0),
+      range_min(0),
+      range_max(0),
+      ranges_length(0), ranges(NULL),
+      intensities_length(0), intensities(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_min;
+      u_angle_min.real = this->angle_min;
+      *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_max;
+      u_angle_max.real = this->angle_max;
+      *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_increment;
+      u_angle_increment.real = this->angle_increment;
+      *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_time_increment;
+      u_time_increment.real = this->time_increment;
+      *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_scan_time;
+      u_scan_time.real = this->scan_time;
+      *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_min;
+      u_range_min.real = this->range_min;
+      *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_max;
+      u_range_max.real = this->range_max;
+      *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_max);
+      *(outbuffer + offset++) = ranges_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < ranges_length; i++){
+      offset += this->ranges[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = intensities_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < intensities_length; i++){
+      offset += this->intensities[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_min;
+      u_angle_min.base = 0;
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_min = u_angle_min.real;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_max;
+      u_angle_max.base = 0;
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_max = u_angle_max.real;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        uint32_t base;
+      } u_angle_increment;
+      u_angle_increment.base = 0;
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_increment = u_angle_increment.real;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_time_increment;
+      u_time_increment.base = 0;
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->time_increment = u_time_increment.real;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        uint32_t base;
+      } u_scan_time;
+      u_scan_time.base = 0;
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->scan_time = u_scan_time.real;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_min;
+      u_range_min.base = 0;
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_min = u_range_min.real;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        uint32_t base;
+      } u_range_max;
+      u_range_max.base = 0;
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_max = u_range_max.real;
+      offset += sizeof(this->range_max);
+      uint8_t ranges_lengthT = *(inbuffer + offset++);
+      if(ranges_lengthT > ranges_length)
+        this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho));
+      offset += 3;
+      ranges_length = ranges_lengthT;
+      for( uint8_t i = 0; i < ranges_length; i++){
+      offset += this->st_ranges.deserialize(inbuffer + offset);
+        memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho));
+      }
+      uint8_t intensities_lengthT = *(inbuffer + offset++);
+      if(intensities_lengthT > intensities_length)
+        this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho));
+      offset += 3;
+      intensities_length = intensities_lengthT;
+      for( uint8_t i = 0; i < intensities_length; i++){
+      offset += this->st_intensities.deserialize(inbuffer + offset);
+        memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; };
+    const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/NavSatFix.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatFix.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,186 @@
+#ifndef _ROS_sensor_msgs_NavSatFix_h
+#define _ROS_sensor_msgs_NavSatFix_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/NavSatStatus.h"
+
+namespace sensor_msgs
+{
+
+  class NavSatFix : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      sensor_msgs::NavSatStatus status;
+      double latitude;
+      double longitude;
+      double altitude;
+      double position_covariance[9];
+      uint8_t position_covariance_type;
+      enum { COVARIANCE_TYPE_UNKNOWN =  0 };
+      enum { COVARIANCE_TYPE_APPROXIMATED =  1 };
+      enum { COVARIANCE_TYPE_DIAGONAL_KNOWN =  2 };
+      enum { COVARIANCE_TYPE_KNOWN =  3 };
+
+    NavSatFix():
+      header(),
+      status(),
+      latitude(0),
+      longitude(0),
+      altitude(0),
+      position_covariance(),
+      position_covariance_type(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_latitude;
+      u_latitude.real = this->latitude;
+      *(outbuffer + offset + 0) = (u_latitude.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_latitude.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_latitude.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_latitude.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_latitude.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_latitude.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_latitude.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_latitude.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->latitude);
+      union {
+        double real;
+        uint64_t base;
+      } u_longitude;
+      u_longitude.real = this->longitude;
+      *(outbuffer + offset + 0) = (u_longitude.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_longitude.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_longitude.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_longitude.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_longitude.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_longitude.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_longitude.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_longitude.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->longitude);
+      union {
+        double real;
+        uint64_t base;
+      } u_altitude;
+      u_altitude.real = this->altitude;
+      *(outbuffer + offset + 0) = (u_altitude.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_altitude.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_altitude.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_altitude.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_altitude.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_altitude.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_altitude.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_altitude.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->altitude);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_position_covariancei;
+      u_position_covariancei.real = this->position_covariance[i];
+      *(outbuffer + offset + 0) = (u_position_covariancei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_position_covariancei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_position_covariancei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_position_covariancei.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_position_covariancei.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_position_covariancei.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_position_covariancei.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_position_covariancei.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->position_covariance[i]);
+      }
+      *(outbuffer + offset + 0) = (this->position_covariance_type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->position_covariance_type);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_latitude;
+      u_latitude.base = 0;
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_latitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->latitude = u_latitude.real;
+      offset += sizeof(this->latitude);
+      union {
+        double real;
+        uint64_t base;
+      } u_longitude;
+      u_longitude.base = 0;
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_longitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->longitude = u_longitude.real;
+      offset += sizeof(this->longitude);
+      union {
+        double real;
+        uint64_t base;
+      } u_altitude;
+      u_altitude.base = 0;
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_altitude.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->altitude = u_altitude.real;
+      offset += sizeof(this->altitude);
+      for( uint8_t i = 0; i < 9; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_position_covariancei;
+      u_position_covariancei.base = 0;
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_position_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->position_covariance[i] = u_position_covariancei.real;
+      offset += sizeof(this->position_covariance[i]);
+      }
+      this->position_covariance_type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->position_covariance_type);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/NavSatFix"; };
+    const char * getMD5(){ return "2d3a8cd499b9b4a0249fb98fd05cfa48"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/NavSatStatus.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatStatus.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,71 @@
+#ifndef _ROS_sensor_msgs_NavSatStatus_h
+#define _ROS_sensor_msgs_NavSatStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class NavSatStatus : public ros::Msg
+  {
+    public:
+      int8_t status;
+      uint16_t service;
+      enum { STATUS_NO_FIX =   -1         };
+      enum { STATUS_FIX =       0         };
+      enum { STATUS_SBAS_FIX =  1         };
+      enum { STATUS_GBAS_FIX =  2         };
+      enum { SERVICE_GPS =      1 };
+      enum { SERVICE_GLONASS =  2 };
+      enum { SERVICE_COMPASS =  4       };
+      enum { SERVICE_GALILEO =  8 };
+
+    NavSatStatus():
+      status(0),
+      service(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_status;
+      u_status.real = this->status;
+      *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->status);
+      *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->service);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_status;
+      u_status.base = 0;
+      u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->status = u_status.real;
+      offset += sizeof(this->status);
+      this->service =  ((uint16_t) (*(inbuffer + offset)));
+      this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->service);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/NavSatStatus"; };
+    const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/PointCloud.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,85 @@
+#ifndef _ROS_sensor_msgs_PointCloud_h
+#define _ROS_sensor_msgs_PointCloud_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point32.h"
+#include "sensor_msgs/ChannelFloat32.h"
+
+namespace sensor_msgs
+{
+
+  class PointCloud : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t points_length;
+      geometry_msgs::Point32 st_points;
+      geometry_msgs::Point32 * points;
+      uint8_t channels_length;
+      sensor_msgs::ChannelFloat32 st_channels;
+      sensor_msgs::ChannelFloat32 * channels;
+
+    PointCloud():
+      header(),
+      points_length(0), points(NULL),
+      channels_length(0), channels(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = channels_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < channels_length; i++){
+      offset += this->channels[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
+      }
+      uint8_t channels_lengthT = *(inbuffer + offset++);
+      if(channels_lengthT > channels_length)
+        this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
+      offset += 3;
+      channels_length = channels_lengthT;
+      for( uint8_t i = 0; i < channels_length; i++){
+      offset += this->st_channels.deserialize(inbuffer + offset);
+        memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/PointCloud"; };
+    const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/PointCloud2.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud2.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,168 @@
+#ifndef _ROS_sensor_msgs_PointCloud2_h
+#define _ROS_sensor_msgs_PointCloud2_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/PointField.h"
+
+namespace sensor_msgs
+{
+
+  class PointCloud2 : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint32_t height;
+      uint32_t width;
+      uint8_t fields_length;
+      sensor_msgs::PointField st_fields;
+      sensor_msgs::PointField * fields;
+      bool is_bigendian;
+      uint32_t point_step;
+      uint32_t row_step;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+      bool is_dense;
+
+    PointCloud2():
+      header(),
+      height(0),
+      width(0),
+      fields_length(0), fields(NULL),
+      is_bigendian(0),
+      point_step(0),
+      row_step(0),
+      data_length(0), data(NULL),
+      is_dense(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      *(outbuffer + offset++) = fields_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < fields_length; i++){
+      offset += this->fields[i].serialize(outbuffer + offset);
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_bigendian;
+      u_is_bigendian.real = this->is_bigendian;
+      *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_bigendian);
+      *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->point_step);
+      *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->row_step);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_dense;
+      u_is_dense.real = this->is_dense;
+      *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_dense);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      uint8_t fields_lengthT = *(inbuffer + offset++);
+      if(fields_lengthT > fields_length)
+        this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
+      offset += 3;
+      fields_length = fields_lengthT;
+      for( uint8_t i = 0; i < fields_length; i++){
+      offset += this->st_fields.deserialize(inbuffer + offset);
+        memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_bigendian;
+      u_is_bigendian.base = 0;
+      u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_bigendian = u_is_bigendian.real;
+      offset += sizeof(this->is_bigendian);
+      this->point_step =  ((uint32_t) (*(inbuffer + offset)));
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->point_step);
+      this->row_step =  ((uint32_t) (*(inbuffer + offset)));
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->row_step);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_is_dense;
+      u_is_dense.base = 0;
+      u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_dense = u_is_dense.real;
+      offset += sizeof(this->is_dense);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/PointCloud2"; };
+    const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/PointField.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointField.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,92 @@
+#ifndef _ROS_sensor_msgs_PointField_h
+#define _ROS_sensor_msgs_PointField_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class PointField : public ros::Msg
+  {
+    public:
+      const char* name;
+      uint32_t offset;
+      uint8_t datatype;
+      uint32_t count;
+      enum { INT8 =  1 };
+      enum { UINT8 =  2 };
+      enum { INT16 =  3 };
+      enum { UINT16 =  4 };
+      enum { INT32 =  5 };
+      enum { UINT32 =  6 };
+      enum { FLOAT32 =  7 };
+      enum { FLOAT64 =  8 };
+
+    PointField():
+      name(""),
+      offset(0),
+      datatype(0),
+      count(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->offset);
+      *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->datatype);
+      *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->count);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      this->offset =  ((uint32_t) (*(inbuffer + offset)));
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->offset);
+      this->datatype =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->datatype);
+      this->count =  ((uint32_t) (*(inbuffer + offset)));
+      this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->count);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/PointField"; };
+    const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Range.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Range.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,143 @@
+#ifndef _ROS_sensor_msgs_Range_h
+#define _ROS_sensor_msgs_Range_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Range : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t radiation_type;
+      float field_of_view;
+      float min_range;
+      float max_range;
+      float range;
+      enum { ULTRASOUND = 0 };
+      enum { INFRARED = 1 };
+
+    Range():
+      header(),
+      radiation_type(0),
+      field_of_view(0),
+      min_range(0),
+      max_range(0),
+      range(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->radiation_type);
+      union {
+        float real;
+        uint32_t base;
+      } u_field_of_view;
+      u_field_of_view.real = this->field_of_view;
+      *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->field_of_view);
+      union {
+        float real;
+        uint32_t base;
+      } u_min_range;
+      u_min_range.real = this->min_range;
+      *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_range);
+      union {
+        float real;
+        uint32_t base;
+      } u_max_range;
+      u_max_range.real = this->max_range;
+      *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->max_range);
+      union {
+        float real;
+        uint32_t base;
+      } u_range;
+      u_range.real = this->range;
+      *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->radiation_type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->radiation_type);
+      union {
+        float real;
+        uint32_t base;
+      } u_field_of_view;
+      u_field_of_view.base = 0;
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->field_of_view = u_field_of_view.real;
+      offset += sizeof(this->field_of_view);
+      union {
+        float real;
+        uint32_t base;
+      } u_min_range;
+      u_min_range.base = 0;
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->min_range = u_min_range.real;
+      offset += sizeof(this->min_range);
+      union {
+        float real;
+        uint32_t base;
+      } u_max_range;
+      u_max_range.base = 0;
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->max_range = u_max_range.real;
+      offset += sizeof(this->max_range);
+      union {
+        float real;
+        uint32_t base;
+      } u_range;
+      u_range.base = 0;
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range = u_range.real;
+      offset += sizeof(this->range);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Range"; };
+    const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/RegionOfInterest.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/RegionOfInterest.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,103 @@
+#ifndef _ROS_sensor_msgs_RegionOfInterest_h
+#define _ROS_sensor_msgs_RegionOfInterest_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class RegionOfInterest : public ros::Msg
+  {
+    public:
+      uint32_t x_offset;
+      uint32_t y_offset;
+      uint32_t height;
+      uint32_t width;
+      bool do_rectify;
+
+    RegionOfInterest():
+      x_offset(0),
+      y_offset(0),
+      height(0),
+      width(0),
+      do_rectify(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x_offset);
+      *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y_offset);
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        bool real;
+        uint8_t base;
+      } u_do_rectify;
+      u_do_rectify.real = this->do_rectify;
+      *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->do_rectify);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->x_offset =  ((uint32_t) (*(inbuffer + offset)));
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->x_offset);
+      this->y_offset =  ((uint32_t) (*(inbuffer + offset)));
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->y_offset);
+      this->height =  ((uint32_t) (*(inbuffer + offset)));
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->height);
+      this->width =  ((uint32_t) (*(inbuffer + offset)));
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->width);
+      union {
+        bool real;
+        uint8_t base;
+      } u_do_rectify;
+      u_do_rectify.base = 0;
+      u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->do_rectify = u_do_rectify.real;
+      offset += sizeof(this->do_rectify);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/RegionOfInterest"; };
+    const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/RelativeHumidity.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/RelativeHumidity.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,105 @@
+#ifndef _ROS_sensor_msgs_RelativeHumidity_h
+#define _ROS_sensor_msgs_RelativeHumidity_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class RelativeHumidity : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double relative_humidity;
+      double variance;
+
+    RelativeHumidity():
+      header(),
+      relative_humidity(0),
+      variance(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_relative_humidity;
+      u_relative_humidity.real = this->relative_humidity;
+      *(outbuffer + offset + 0) = (u_relative_humidity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_relative_humidity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_relative_humidity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_relative_humidity.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_relative_humidity.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_relative_humidity.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_relative_humidity.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_relative_humidity.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->relative_humidity);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.real = this->variance;
+      *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->variance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_relative_humidity;
+      u_relative_humidity.base = 0;
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_relative_humidity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->relative_humidity = u_relative_humidity.real;
+      offset += sizeof(this->relative_humidity);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.base = 0;
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->variance = u_variance.real;
+      offset += sizeof(this->variance);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/RelativeHumidity"; };
+    const char * getMD5(){ return "8730015b05955b7e992ce29a2678d90f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/SetCameraInfo.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/SetCameraInfo.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,108 @@
+#ifndef _ROS_SERVICE_SetCameraInfo_h
+#define _ROS_SERVICE_SetCameraInfo_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "sensor_msgs/CameraInfo.h"
+
+namespace sensor_msgs
+{
+
+static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo";
+
+  class SetCameraInfoRequest : public ros::Msg
+  {
+    public:
+      sensor_msgs::CameraInfo camera_info;
+
+    SetCameraInfoRequest():
+      camera_info()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->camera_info.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->camera_info.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETCAMERAINFO; };
+    const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
+
+  };
+
+  class SetCameraInfoResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* status_message;
+
+    SetCameraInfoResponse():
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = strlen(this->status_message);
+      memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, length_status_message);
+      offset += length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message;
+      memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+    const char * getType(){ return SETCAMERAINFO; };
+    const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
+
+  class SetCameraInfo {
+    public:
+    typedef SetCameraInfoRequest Request;
+    typedef SetCameraInfoResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/Temperature.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Temperature.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,105 @@
+#ifndef _ROS_sensor_msgs_Temperature_h
+#define _ROS_sensor_msgs_Temperature_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Temperature : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      double temperature;
+      double variance;
+
+    Temperature():
+      header(),
+      temperature(0),
+      variance(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_temperature;
+      u_temperature.real = this->temperature;
+      *(outbuffer + offset + 0) = (u_temperature.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_temperature.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_temperature.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_temperature.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_temperature.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_temperature.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_temperature.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_temperature.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->temperature);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.real = this->variance;
+      *(outbuffer + offset + 0) = (u_variance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_variance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_variance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_variance.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_variance.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_variance.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_variance.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_variance.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->variance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        double real;
+        uint64_t base;
+      } u_temperature;
+      u_temperature.base = 0;
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_temperature.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->temperature = u_temperature.real;
+      offset += sizeof(this->temperature);
+      union {
+        double real;
+        uint64_t base;
+      } u_variance;
+      u_variance.base = 0;
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_variance.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->variance = u_variance.real;
+      offset += sizeof(this->variance);
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/Temperature"; };
+    const char * getMD5(){ return "ff71b307acdbe7c871a5a6d7ed359100"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 sensor_msgs/TimeReference.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/TimeReference.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_sensor_msgs_TimeReference_h
+#define _ROS_sensor_msgs_TimeReference_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "ros/time.h"
+
+namespace sensor_msgs
+{
+
+  class TimeReference : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      ros::Time time_ref;
+      const char* source;
+
+    TimeReference():
+      header(),
+      time_ref(),
+      source("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->time_ref.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_ref.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_ref.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_ref.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_ref.sec);
+      *(outbuffer + offset + 0) = (this->time_ref.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_ref.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_ref.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_ref.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_ref.nsec);
+      uint32_t length_source = strlen(this->source);
+      memcpy(outbuffer + offset, &length_source, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->source, length_source);
+      offset += length_source;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->time_ref.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_ref.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_ref.sec);
+      this->time_ref.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_ref.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_ref.nsec);
+      uint32_t length_source;
+      memcpy(&length_source, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_source; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_source-1]=0;
+      this->source = (char *)(inbuffer + offset-1);
+      offset += length_source;
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/TimeReference"; };
+    const char * getMD5(){ return "fded64a0265108ba86c3d38fb11c0c16"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 shape_msgs/Mesh.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/Mesh.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,80 @@
+#ifndef _ROS_shape_msgs_Mesh_h
+#define _ROS_shape_msgs_Mesh_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "shape_msgs/MeshTriangle.h"
+#include "geometry_msgs/Point.h"
+
+namespace shape_msgs
+{
+
+  class Mesh : public ros::Msg
+  {
+    public:
+      uint8_t triangles_length;
+      shape_msgs::MeshTriangle st_triangles;
+      shape_msgs::MeshTriangle * triangles;
+      uint8_t vertices_length;
+      geometry_msgs::Point st_vertices;
+      geometry_msgs::Point * vertices;
+
+    Mesh():
+      triangles_length(0), triangles(NULL),
+      vertices_length(0), vertices(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = triangles_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < triangles_length; i++){
+      offset += this->triangles[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = vertices_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < vertices_length; i++){
+      offset += this->vertices[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t triangles_lengthT = *(inbuffer + offset++);
+      if(triangles_lengthT > triangles_length)
+        this->triangles = (shape_msgs::MeshTriangle*)realloc(this->triangles, triangles_lengthT * sizeof(shape_msgs::MeshTriangle));
+      offset += 3;
+      triangles_length = triangles_lengthT;
+      for( uint8_t i = 0; i < triangles_length; i++){
+      offset += this->st_triangles.deserialize(inbuffer + offset);
+        memcpy( &(this->triangles[i]), &(this->st_triangles), sizeof(shape_msgs::MeshTriangle));
+      }
+      uint8_t vertices_lengthT = *(inbuffer + offset++);
+      if(vertices_lengthT > vertices_length)
+        this->vertices = (geometry_msgs::Point*)realloc(this->vertices, vertices_lengthT * sizeof(geometry_msgs::Point));
+      offset += 3;
+      vertices_length = vertices_lengthT;
+      for( uint8_t i = 0; i < vertices_length; i++){
+      offset += this->st_vertices.deserialize(inbuffer + offset);
+        memcpy( &(this->vertices[i]), &(this->st_vertices), sizeof(geometry_msgs::Point));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "shape_msgs/Mesh"; };
+    const char * getMD5(){ return "1ffdae9486cd3316a121c578b47a85cc"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 shape_msgs/MeshTriangle.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/MeshTriangle.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,54 @@
+#ifndef _ROS_shape_msgs_MeshTriangle_h
+#define _ROS_shape_msgs_MeshTriangle_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace shape_msgs
+{
+
+  class MeshTriangle : public ros::Msg
+  {
+    public:
+      uint32_t vertex_indices[3];
+
+    MeshTriangle():
+      vertex_indices()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      for( uint8_t i = 0; i < 3; i++){
+      *(outbuffer + offset + 0) = (this->vertex_indices[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->vertex_indices[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->vertex_indices[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->vertex_indices[i] >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->vertex_indices[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      for( uint8_t i = 0; i < 3; i++){
+      this->vertex_indices[i] =  ((uint32_t) (*(inbuffer + offset)));
+      this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->vertex_indices[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "shape_msgs/MeshTriangle"; };
+    const char * getMD5(){ return "23688b2e6d2de3d32fe8af104a903253"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 shape_msgs/Plane.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/Plane.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,73 @@
+#ifndef _ROS_shape_msgs_Plane_h
+#define _ROS_shape_msgs_Plane_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace shape_msgs
+{
+
+  class Plane : public ros::Msg
+  {
+    public:
+      double coef[4];
+
+    Plane():
+      coef()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      for( uint8_t i = 0; i < 4; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_coefi;
+      u_coefi.real = this->coef[i];
+      *(outbuffer + offset + 0) = (u_coefi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_coefi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_coefi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_coefi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_coefi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_coefi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_coefi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_coefi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->coef[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      for( uint8_t i = 0; i < 4; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_coefi;
+      u_coefi.base = 0;
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_coefi.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->coef[i] = u_coefi.real;
+      offset += sizeof(this->coef[i]);
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "shape_msgs/Plane"; };
+    const char * getMD5(){ return "2c1b92ed8f31492f8e73f6a4a44ca796"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 shape_msgs/SolidPrimitive.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/SolidPrimitive.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,103 @@
+#ifndef _ROS_shape_msgs_SolidPrimitive_h
+#define _ROS_shape_msgs_SolidPrimitive_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace shape_msgs
+{
+
+  class SolidPrimitive : public ros::Msg
+  {
+    public:
+      uint8_t type;
+      uint8_t dimensions_length;
+      double st_dimensions;
+      double * dimensions;
+      enum { BOX = 1 };
+      enum { SPHERE = 2 };
+      enum { CYLINDER = 3 };
+      enum { CONE = 4 };
+      enum { BOX_X = 0 };
+      enum { BOX_Y = 1 };
+      enum { BOX_Z = 2 };
+      enum { SPHERE_RADIUS = 0 };
+      enum { CYLINDER_HEIGHT = 0 };
+      enum { CYLINDER_RADIUS = 1 };
+      enum { CONE_HEIGHT = 0 };
+      enum { CONE_RADIUS = 1 };
+
+    SolidPrimitive():
+      type(0),
+      dimensions_length(0), dimensions(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->type);
+      *(outbuffer + offset++) = dimensions_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < dimensions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_dimensionsi;
+      u_dimensionsi.real = this->dimensions[i];
+      *(outbuffer + offset + 0) = (u_dimensionsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_dimensionsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_dimensionsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_dimensionsi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_dimensionsi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_dimensionsi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_dimensionsi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_dimensionsi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->dimensions[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->type);
+      uint8_t dimensions_lengthT = *(inbuffer + offset++);
+      if(dimensions_lengthT > dimensions_length)
+        this->dimensions = (double*)realloc(this->dimensions, dimensions_lengthT * sizeof(double));
+      offset += 3;
+      dimensions_length = dimensions_lengthT;
+      for( uint8_t i = 0; i < dimensions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_dimensions;
+      u_st_dimensions.base = 0;
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_dimensions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_dimensions = u_st_dimensions.real;
+      offset += sizeof(this->st_dimensions);
+        memcpy( &(this->dimensions[i]), &(this->st_dimensions), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "shape_msgs/SolidPrimitive"; };
+    const char * getMD5(){ return "d8f8cbc74c5ff283fca29569ccefb45d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 smach_msgs/SmachContainerInitialStatusCmd.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerInitialStatusCmd.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_smach_msgs_SmachContainerInitialStatusCmd_h
+#define _ROS_smach_msgs_SmachContainerInitialStatusCmd_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace smach_msgs
+{
+
+  class SmachContainerInitialStatusCmd : public ros::Msg
+  {
+    public:
+      const char* path;
+      uint8_t initial_states_length;
+      char* st_initial_states;
+      char* * initial_states;
+      const char* local_data;
+
+    SmachContainerInitialStatusCmd():
+      path(""),
+      initial_states_length(0), initial_states(NULL),
+      local_data("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_path = strlen(this->path);
+      memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset++) = initial_states_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < initial_states_length; i++){
+      uint32_t length_initial_statesi = strlen(this->initial_states[i]);
+      memcpy(outbuffer + offset, &length_initial_statesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi);
+      offset += length_initial_statesi;
+      }
+      uint32_t length_local_data = strlen(this->local_data);
+      memcpy(outbuffer + offset, &length_local_data, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->local_data, length_local_data);
+      offset += length_local_data;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_path;
+      memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_path; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_path-1]=0;
+      this->path = (char *)(inbuffer + offset-1);
+      offset += length_path;
+      uint8_t initial_states_lengthT = *(inbuffer + offset++);
+      if(initial_states_lengthT > initial_states_length)
+        this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*));
+      offset += 3;
+      initial_states_length = initial_states_lengthT;
+      for( uint8_t i = 0; i < initial_states_length; i++){
+      uint32_t length_st_initial_states;
+      memcpy(&length_st_initial_states, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_initial_states; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_initial_states-1]=0;
+      this->st_initial_states = (char *)(inbuffer + offset-1);
+      offset += length_st_initial_states;
+        memcpy( &(this->initial_states[i]), &(this->st_initial_states), sizeof(char*));
+      }
+      uint32_t length_local_data;
+      memcpy(&length_local_data, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_local_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_local_data-1]=0;
+      this->local_data = (char *)(inbuffer + offset-1);
+      offset += length_local_data;
+     return offset;
+    }
+
+    const char * getType(){ return "smach_msgs/SmachContainerInitialStatusCmd"; };
+    const char * getMD5(){ return "45f8cf31fc29b829db77f23001f788d6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 smach_msgs/SmachContainerStatus.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerStatus.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,155 @@
+#ifndef _ROS_smach_msgs_SmachContainerStatus_h
+#define _ROS_smach_msgs_SmachContainerStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace smach_msgs
+{
+
+  class SmachContainerStatus : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* path;
+      uint8_t initial_states_length;
+      char* st_initial_states;
+      char* * initial_states;
+      uint8_t active_states_length;
+      char* st_active_states;
+      char* * active_states;
+      const char* local_data;
+      const char* info;
+
+    SmachContainerStatus():
+      header(),
+      path(""),
+      initial_states_length(0), initial_states(NULL),
+      active_states_length(0), active_states(NULL),
+      local_data(""),
+      info("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_path = strlen(this->path);
+      memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset++) = initial_states_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < initial_states_length; i++){
+      uint32_t length_initial_statesi = strlen(this->initial_states[i]);
+      memcpy(outbuffer + offset, &length_initial_statesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi);
+      offset += length_initial_statesi;
+      }
+      *(outbuffer + offset++) = active_states_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < active_states_length; i++){
+      uint32_t length_active_statesi = strlen(this->active_states[i]);
+      memcpy(outbuffer + offset, &length_active_statesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->active_states[i], length_active_statesi);
+      offset += length_active_statesi;
+      }
+      uint32_t length_local_data = strlen(this->local_data);
+      memcpy(outbuffer + offset, &length_local_data, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->local_data, length_local_data);
+      offset += length_local_data;
+      uint32_t length_info = strlen(this->info);
+      memcpy(outbuffer + offset, &length_info, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->info, length_info);
+      offset += length_info;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_path;
+      memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_path; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_path-1]=0;
+      this->path = (char *)(inbuffer + offset-1);
+      offset += length_path;
+      uint8_t initial_states_lengthT = *(inbuffer + offset++);
+      if(initial_states_lengthT > initial_states_length)
+        this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*));
+      offset += 3;
+      initial_states_length = initial_states_lengthT;
+      for( uint8_t i = 0; i < initial_states_length; i++){
+      uint32_t length_st_initial_states;
+      memcpy(&length_st_initial_states, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_initial_states; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_initial_states-1]=0;
+      this->st_initial_states = (char *)(inbuffer + offset-1);
+      offset += length_st_initial_states;
+        memcpy( &(this->initial_states[i]), &(this->st_initial_states), sizeof(char*));
+      }
+      uint8_t active_states_lengthT = *(inbuffer + offset++);
+      if(active_states_lengthT > active_states_length)
+        this->active_states = (char**)realloc(this->active_states, active_states_lengthT * sizeof(char*));
+      offset += 3;
+      active_states_length = active_states_lengthT;
+      for( uint8_t i = 0; i < active_states_length; i++){
+      uint32_t length_st_active_states;
+      memcpy(&length_st_active_states, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_active_states; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_active_states-1]=0;
+      this->st_active_states = (char *)(inbuffer + offset-1);
+      offset += length_st_active_states;
+        memcpy( &(this->active_states[i]), &(this->st_active_states), sizeof(char*));
+      }
+      uint32_t length_local_data;
+      memcpy(&length_local_data, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_local_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_local_data-1]=0;
+      this->local_data = (char *)(inbuffer + offset-1);
+      offset += length_local_data;
+      uint32_t length_info;
+      memcpy(&length_info, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_info; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_info-1]=0;
+      this->info = (char *)(inbuffer + offset-1);
+      offset += length_info;
+     return offset;
+    }
+
+    const char * getType(){ return "smach_msgs/SmachContainerStatus"; };
+    const char * getMD5(){ return "5ba2bb79ac19e3842d562a191f2a675b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 smach_msgs/SmachContainerStructure.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerStructure.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,219 @@
+#ifndef _ROS_smach_msgs_SmachContainerStructure_h
+#define _ROS_smach_msgs_SmachContainerStructure_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace smach_msgs
+{
+
+  class SmachContainerStructure : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* path;
+      uint8_t children_length;
+      char* st_children;
+      char* * children;
+      uint8_t internal_outcomes_length;
+      char* st_internal_outcomes;
+      char* * internal_outcomes;
+      uint8_t outcomes_from_length;
+      char* st_outcomes_from;
+      char* * outcomes_from;
+      uint8_t outcomes_to_length;
+      char* st_outcomes_to;
+      char* * outcomes_to;
+      uint8_t container_outcomes_length;
+      char* st_container_outcomes;
+      char* * container_outcomes;
+
+    SmachContainerStructure():
+      header(),
+      path(""),
+      children_length(0), children(NULL),
+      internal_outcomes_length(0), internal_outcomes(NULL),
+      outcomes_from_length(0), outcomes_from(NULL),
+      outcomes_to_length(0), outcomes_to(NULL),
+      container_outcomes_length(0), container_outcomes(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_path = strlen(this->path);
+      memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset++) = children_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < children_length; i++){
+      uint32_t length_childreni = strlen(this->children[i]);
+      memcpy(outbuffer + offset, &length_childreni, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->children[i], length_childreni);
+      offset += length_childreni;
+      }
+      *(outbuffer + offset++) = internal_outcomes_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < internal_outcomes_length; i++){
+      uint32_t length_internal_outcomesi = strlen(this->internal_outcomes[i]);
+      memcpy(outbuffer + offset, &length_internal_outcomesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->internal_outcomes[i], length_internal_outcomesi);
+      offset += length_internal_outcomesi;
+      }
+      *(outbuffer + offset++) = outcomes_from_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < outcomes_from_length; i++){
+      uint32_t length_outcomes_fromi = strlen(this->outcomes_from[i]);
+      memcpy(outbuffer + offset, &length_outcomes_fromi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->outcomes_from[i], length_outcomes_fromi);
+      offset += length_outcomes_fromi;
+      }
+      *(outbuffer + offset++) = outcomes_to_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < outcomes_to_length; i++){
+      uint32_t length_outcomes_toi = strlen(this->outcomes_to[i]);
+      memcpy(outbuffer + offset, &length_outcomes_toi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->outcomes_to[i], length_outcomes_toi);
+      offset += length_outcomes_toi;
+      }
+      *(outbuffer + offset++) = container_outcomes_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < container_outcomes_length; i++){
+      uint32_t length_container_outcomesi = strlen(this->container_outcomes[i]);
+      memcpy(outbuffer + offset, &length_container_outcomesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->container_outcomes[i], length_container_outcomesi);
+      offset += length_container_outcomesi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_path;
+      memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_path; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_path-1]=0;
+      this->path = (char *)(inbuffer + offset-1);
+      offset += length_path;
+      uint8_t children_lengthT = *(inbuffer + offset++);
+      if(children_lengthT > children_length)
+        this->children = (char**)realloc(this->children, children_lengthT * sizeof(char*));
+      offset += 3;
+      children_length = children_lengthT;
+      for( uint8_t i = 0; i < children_length; i++){
+      uint32_t length_st_children;
+      memcpy(&length_st_children, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_children; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_children-1]=0;
+      this->st_children = (char *)(inbuffer + offset-1);
+      offset += length_st_children;
+        memcpy( &(this->children[i]), &(this->st_children), sizeof(char*));
+      }
+      uint8_t internal_outcomes_lengthT = *(inbuffer + offset++);
+      if(internal_outcomes_lengthT > internal_outcomes_length)
+        this->internal_outcomes = (char**)realloc(this->internal_outcomes, internal_outcomes_lengthT * sizeof(char*));
+      offset += 3;
+      internal_outcomes_length = internal_outcomes_lengthT;
+      for( uint8_t i = 0; i < internal_outcomes_length; i++){
+      uint32_t length_st_internal_outcomes;
+      memcpy(&length_st_internal_outcomes, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_internal_outcomes; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_internal_outcomes-1]=0;
+      this->st_internal_outcomes = (char *)(inbuffer + offset-1);
+      offset += length_st_internal_outcomes;
+        memcpy( &(this->internal_outcomes[i]), &(this->st_internal_outcomes), sizeof(char*));
+      }
+      uint8_t outcomes_from_lengthT = *(inbuffer + offset++);
+      if(outcomes_from_lengthT > outcomes_from_length)
+        this->outcomes_from = (char**)realloc(this->outcomes_from, outcomes_from_lengthT * sizeof(char*));
+      offset += 3;
+      outcomes_from_length = outcomes_from_lengthT;
+      for( uint8_t i = 0; i < outcomes_from_length; i++){
+      uint32_t length_st_outcomes_from;
+      memcpy(&length_st_outcomes_from, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_outcomes_from; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_outcomes_from-1]=0;
+      this->st_outcomes_from = (char *)(inbuffer + offset-1);
+      offset += length_st_outcomes_from;
+        memcpy( &(this->outcomes_from[i]), &(this->st_outcomes_from), sizeof(char*));
+      }
+      uint8_t outcomes_to_lengthT = *(inbuffer + offset++);
+      if(outcomes_to_lengthT > outcomes_to_length)
+        this->outcomes_to = (char**)realloc(this->outcomes_to, outcomes_to_lengthT * sizeof(char*));
+      offset += 3;
+      outcomes_to_length = outcomes_to_lengthT;
+      for( uint8_t i = 0; i < outcomes_to_length; i++){
+      uint32_t length_st_outcomes_to;
+      memcpy(&length_st_outcomes_to, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_outcomes_to; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_outcomes_to-1]=0;
+      this->st_outcomes_to = (char *)(inbuffer + offset-1);
+      offset += length_st_outcomes_to;
+        memcpy( &(this->outcomes_to[i]), &(this->st_outcomes_to), sizeof(char*));
+      }
+      uint8_t container_outcomes_lengthT = *(inbuffer + offset++);
+      if(container_outcomes_lengthT > container_outcomes_length)
+        this->container_outcomes = (char**)realloc(this->container_outcomes, container_outcomes_lengthT * sizeof(char*));
+      offset += 3;
+      container_outcomes_length = container_outcomes_lengthT;
+      for( uint8_t i = 0; i < container_outcomes_length; i++){
+      uint32_t length_st_container_outcomes;
+      memcpy(&length_st_container_outcomes, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_container_outcomes; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_container_outcomes-1]=0;
+      this->st_container_outcomes = (char *)(inbuffer + offset-1);
+      offset += length_st_container_outcomes;
+        memcpy( &(this->container_outcomes[i]), &(this->st_container_outcomes), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "smach_msgs/SmachContainerStructure"; };
+    const char * getMD5(){ return "3d3d1e0d0f99779ee9e58101a5dcf7ea"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Bool.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Bool.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,55 @@
+#ifndef _ROS_std_msgs_Bool_h
+#define _ROS_std_msgs_Bool_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Bool : public ros::Msg
+  {
+    public:
+      bool data;
+
+    Bool():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Bool"; };
+    const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Byte.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Byte.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,55 @@
+#ifndef _ROS_std_msgs_Byte_h
+#define _ROS_std_msgs_Byte_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Byte : public ros::Msg
+  {
+    public:
+      int8_t data;
+
+    Byte():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Byte"; };
+    const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/ByteMultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ByteMultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_std_msgs_ByteMultiArray_h
+#define _ROS_std_msgs_ByteMultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class ByteMultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
+
+    ByteMultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/ByteMultiArray"; };
+    const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Char.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Char.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,44 @@
+#ifndef _ROS_std_msgs_Char_h
+#define _ROS_std_msgs_Char_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Char : public ros::Msg
+  {
+    public:
+      uint8_t data;
+
+    Char():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Char"; };
+    const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/ColorRGBA.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ColorRGBA.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,130 @@
+#ifndef _ROS_std_msgs_ColorRGBA_h
+#define _ROS_std_msgs_ColorRGBA_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class ColorRGBA : public ros::Msg
+  {
+    public:
+      float r;
+      float g;
+      float b;
+      float a;
+
+    ColorRGBA():
+      r(0),
+      g(0),
+      b(0),
+      a(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_r;
+      u_r.real = this->r;
+      *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        uint32_t base;
+      } u_g;
+      u_g.real = this->g;
+      *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        uint32_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        uint32_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->a);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_r;
+      u_r.base = 0;
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->r = u_r.real;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        uint32_t base;
+      } u_g;
+      u_g.base = 0;
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->g = u_g.real;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        uint32_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        uint32_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/ColorRGBA"; };
+    const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Duration.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Duration.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_std_msgs_Duration_h
+#define _ROS_std_msgs_Duration_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+
+namespace std_msgs
+{
+
+  class Duration : public ros::Msg
+  {
+    public:
+      ros::Duration data;
+
+    Duration():
+      data()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.sec);
+      this->data.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Duration"; };
+    const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Empty.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Empty.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_std_msgs_Empty_h
+#define _ROS_std_msgs_Empty_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Empty : public ros::Msg
+  {
+    public:
+
+    Empty()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Empty"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Float32.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_std_msgs_Float32_h
+#define _ROS_std_msgs_Float32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float32 : public ros::Msg
+  {
+    public:
+      float data;
+
+    Float32():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Float32"; };
+    const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Float32MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_std_msgs_Float32MultiArray_h
+#define _ROS_std_msgs_Float32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      float st_data;
+      float * data;
+
+    Float32MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Float32MultiArray"; };
+    const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Float64.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_std_msgs_Float64_h
+#define _ROS_std_msgs_Float64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float64 : public ros::Msg
+  {
+    public:
+      double data;
+
+    Float64():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Float64"; };
+    const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Float64MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,90 @@
+#ifndef _ROS_std_msgs_Float64MultiArray_h
+#define _ROS_std_msgs_Float64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      double st_data;
+      double * data;
+
+    Float64MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (double*)realloc(this->data, data_lengthT * sizeof(double));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(double));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Float64MultiArray"; };
+    const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Header.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Header.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,89 @@
+#ifndef _ROS_std_msgs_Header_h
+#define _ROS_std_msgs_Header_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Header : public ros::Msg
+  {
+    public:
+      uint32_t seq;
+      ros::Time stamp;
+      const char* frame_id;
+
+    Header():
+      seq(0),
+      stamp(),
+      frame_id("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->seq);
+      *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.sec);
+      *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_frame_id = strlen(this->frame_id);
+      memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->frame_id, length_frame_id);
+      offset += length_frame_id;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->seq =  ((uint32_t) (*(inbuffer + offset)));
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->seq);
+      this->stamp.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.sec);
+      this->stamp.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_frame_id;
+      memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_frame_id-1]=0;
+      this->frame_id = (char *)(inbuffer + offset-1);
+      offset += length_frame_id;
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Header"; };
+    const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int16.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,57 @@
+#ifndef _ROS_std_msgs_Int16_h
+#define _ROS_std_msgs_Int16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int16 : public ros::Msg
+  {
+    public:
+      int16_t data;
+
+    Int16():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int16"; };
+    const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int16MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_std_msgs_Int16MultiArray_h
+#define _ROS_std_msgs_Int16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int16_t st_data;
+      int16_t * data;
+
+    Int16MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int16MultiArray"; };
+    const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int32.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_std_msgs_Int32_h
+#define _ROS_std_msgs_Int32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int32 : public ros::Msg
+  {
+    public:
+      int32_t data;
+
+    Int32():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int32"; };
+    const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int32MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_std_msgs_Int32MultiArray_h
+#define _ROS_std_msgs_Int32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int32_t st_data;
+      int32_t * data;
+
+    Int32MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int32MultiArray"; };
+    const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int64.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,69 @@
+#ifndef _ROS_std_msgs_Int64_h
+#define _ROS_std_msgs_Int64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int64 : public ros::Msg
+  {
+    public:
+      int64_t data;
+
+    Int64():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int64"; };
+    const char * getMD5(){ return "34add168574510e6e17f5d23ecc077ef"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int64MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,90 @@
+#ifndef _ROS_std_msgs_Int64MultiArray_h
+#define _ROS_std_msgs_Int64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int64_t st_data;
+      int64_t * data;
+
+    Int64MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int64MultiArray"; };
+    const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int8.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,55 @@
+#ifndef _ROS_std_msgs_Int8_h
+#define _ROS_std_msgs_Int8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int8 : public ros::Msg
+  {
+    public:
+      int8_t data;
+
+    Int8():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int8"; };
+    const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Int8MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_std_msgs_Int8MultiArray_h
+#define _ROS_std_msgs_Int8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
+
+    Int8MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Int8MultiArray"; };
+    const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/MultiArrayDimension.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayDimension.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,78 @@
+#ifndef _ROS_std_msgs_MultiArrayDimension_h
+#define _ROS_std_msgs_MultiArrayDimension_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayDimension : public ros::Msg
+  {
+    public:
+      const char* label;
+      uint32_t size;
+      uint32_t stride;
+
+    MultiArrayDimension():
+      label(""),
+      size(0),
+      stride(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_label = strlen(this->label);
+      memcpy(outbuffer + offset, &length_label, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->label, length_label);
+      offset += length_label;
+      *(outbuffer + offset + 0) = (this->size >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->size >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->size >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->size >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->size);
+      *(outbuffer + offset + 0) = (this->stride >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stride >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stride >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stride >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stride);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_label;
+      memcpy(&length_label, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_label; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_label-1]=0;
+      this->label = (char *)(inbuffer + offset-1);
+      offset += length_label;
+      this->size =  ((uint32_t) (*(inbuffer + offset)));
+      this->size |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->size |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->size |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->size);
+      this->stride =  ((uint32_t) (*(inbuffer + offset)));
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stride);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/MultiArrayDimension"; };
+    const char * getMD5(){ return "4cd0c83a8683deae40ecdac60e53bfa8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/MultiArrayLayout.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayLayout.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,71 @@
+#ifndef _ROS_std_msgs_MultiArrayLayout_h
+#define _ROS_std_msgs_MultiArrayLayout_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayDimension.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayLayout : public ros::Msg
+  {
+    public:
+      uint8_t dim_length;
+      std_msgs::MultiArrayDimension st_dim;
+      std_msgs::MultiArrayDimension * dim;
+      uint32_t data_offset;
+
+    MultiArrayLayout():
+      dim_length(0), dim(NULL),
+      data_offset(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = dim_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < dim_length; i++){
+      offset += this->dim[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->data_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_offset >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t dim_lengthT = *(inbuffer + offset++);
+      if(dim_lengthT > dim_length)
+        this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension));
+      offset += 3;
+      dim_length = dim_lengthT;
+      for( uint8_t i = 0; i < dim_length; i++){
+      offset += this->st_dim.deserialize(inbuffer + offset);
+        memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension));
+      }
+      this->data_offset =  ((uint32_t) (*(inbuffer + offset)));
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data_offset);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/MultiArrayLayout"; };
+    const char * getMD5(){ return "0fed2a11c13e11c5571b4e2a995a91a3"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/String.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/String.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,54 @@
+#ifndef _ROS_std_msgs_String_h
+#define _ROS_std_msgs_String_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class String : public ros::Msg
+  {
+    public:
+      const char* data;
+
+    String():
+      data("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_data = strlen(this->data);
+      memcpy(outbuffer + offset, &length_data, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->data, length_data);
+      offset += length_data;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_data;
+      memcpy(&length_data, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_data-1]=0;
+      this->data = (char *)(inbuffer + offset-1);
+      offset += length_data;
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/String"; };
+    const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/Time.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Time.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_std_msgs_Time_h
+#define _ROS_std_msgs_Time_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Time : public ros::Msg
+  {
+    public:
+      ros::Time data;
+
+    Time():
+      data()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.sec);
+      this->data.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/Time"; };
+    const char * getMD5(){ return "cd7166c74c552c311fbcc2fe5a7bc289"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt16.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,46 @@
+#ifndef _ROS_std_msgs_UInt16_h
+#define _ROS_std_msgs_UInt16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt16 : public ros::Msg
+  {
+    public:
+      uint16_t data;
+
+    UInt16():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data =  ((uint16_t) (*(inbuffer + offset)));
+      this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt16"; };
+    const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt16MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,67 @@
+#ifndef _ROS_std_msgs_UInt16MultiArray_h
+#define _ROS_std_msgs_UInt16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint16_t st_data;
+      uint16_t * data;
+
+    UInt16MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint16_t) (*(inbuffer + offset)));
+      this->st_data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt16MultiArray"; };
+    const char * getMD5(){ return "52f264f1c973c4b73790d384c6cb4484"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt32.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,50 @@
+#ifndef _ROS_std_msgs_UInt32_h
+#define _ROS_std_msgs_UInt32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt32 : public ros::Msg
+  {
+    public:
+      uint32_t data;
+
+    UInt32():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data =  ((uint32_t) (*(inbuffer + offset)));
+      this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt32"; };
+    const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt32MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,71 @@
+#ifndef _ROS_std_msgs_UInt32MultiArray_h
+#define _ROS_std_msgs_UInt32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint32_t st_data;
+      uint32_t * data;
+
+    UInt32MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint32_t) (*(inbuffer + offset)));
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt32MultiArray"; };
+    const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt64.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,61 @@
+#ifndef _ROS_std_msgs_UInt64_h
+#define _ROS_std_msgs_UInt64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt64 : public ros::Msg
+  {
+    public:
+      uint64_t data;
+
+    UInt64():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt64"; };
+    const char * getMD5(){ return "1b2a79973e8bf53d7b53acb71299cb57"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt64MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_std_msgs_UInt64MultiArray_h
+#define _ROS_std_msgs_UInt64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint64_t st_data;
+      uint64_t * data;
+
+    UInt64MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt64MultiArray"; };
+    const char * getMD5(){ return "6088f127afb1d6c72927aa1247e945af"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt8.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,44 @@
+#ifndef _ROS_std_msgs_UInt8_h
+#define _ROS_std_msgs_UInt8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt8 : public ros::Msg
+  {
+    public:
+      uint8_t data;
+
+    UInt8():
+      data(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt8"; };
+    const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_msgs/UInt8MultiArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8MultiArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,65 @@
+#ifndef _ROS_std_msgs_UInt8MultiArray_h
+#define _ROS_std_msgs_UInt8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+
+    UInt8MultiArray():
+      layout(),
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "std_msgs/UInt8MultiArray"; };
+    const char * getMD5(){ return "82373f1612381bb6ee473b5cd6f5d89c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 std_srvs/Empty.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_srvs/Empty.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,70 @@
+#ifndef _ROS_SERVICE_Empty_h
+#define _ROS_SERVICE_Empty_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_srvs
+{
+
+static const char EMPTY[] = "std_srvs/Empty";
+
+  class EmptyRequest : public ros::Msg
+  {
+    public:
+
+    EmptyRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return EMPTY; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class EmptyResponse : public ros::Msg
+  {
+    public:
+
+    EmptyResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return EMPTY; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class Empty {
+    public:
+    typedef EmptyRequest Request;
+    typedef EmptyResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 std_srvs/Trigger.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_srvs/Trigger.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,103 @@
+#ifndef _ROS_SERVICE_Trigger_h
+#define _ROS_SERVICE_Trigger_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_srvs
+{
+
+static const char TRIGGER[] = "std_srvs/Trigger";
+
+  class TriggerRequest : public ros::Msg
+  {
+    public:
+
+    TriggerRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return TRIGGER; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class TriggerResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      const char* message;
+
+    TriggerResponse():
+      success(0),
+      message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      uint32_t length_message = strlen(this->message);
+      memcpy(outbuffer + offset, &length_message, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->message, length_message);
+      offset += length_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_message;
+      memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_message-1]=0;
+      this->message = (char *)(inbuffer + offset-1);
+      offset += length_message;
+     return offset;
+    }
+
+    const char * getType(){ return TRIGGER; };
+    const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; };
+
+  };
+
+  class Trigger {
+    public:
+    typedef TriggerRequest Request;
+    typedef TriggerResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 stereo_msgs/DisparityImage.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/stereo_msgs/DisparityImage.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,168 @@
+#ifndef _ROS_stereo_msgs_DisparityImage_h
+#define _ROS_stereo_msgs_DisparityImage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/Image.h"
+#include "sensor_msgs/RegionOfInterest.h"
+
+namespace stereo_msgs
+{
+
+  class DisparityImage : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      sensor_msgs::Image image;
+      float f;
+      float T;
+      sensor_msgs::RegionOfInterest valid_window;
+      float min_disparity;
+      float max_disparity;
+      float delta_d;
+
+    DisparityImage():
+      header(),
+      image(),
+      f(0),
+      T(0),
+      valid_window(),
+      min_disparity(0),
+      max_disparity(0),
+      delta_d(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->image.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_f;
+      u_f.real = this->f;
+      *(outbuffer + offset + 0) = (u_f.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_f.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_f.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_f.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->f);
+      union {
+        float real;
+        uint32_t base;
+      } u_T;
+      u_T.real = this->T;
+      *(outbuffer + offset + 0) = (u_T.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_T.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_T.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_T.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->T);
+      offset += this->valid_window.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_min_disparity;
+      u_min_disparity.real = this->min_disparity;
+      *(outbuffer + offset + 0) = (u_min_disparity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_min_disparity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_min_disparity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_min_disparity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_disparity);
+      union {
+        float real;
+        uint32_t base;
+      } u_max_disparity;
+      u_max_disparity.real = this->max_disparity;
+      *(outbuffer + offset + 0) = (u_max_disparity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_disparity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_disparity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_disparity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->max_disparity);
+      union {
+        float real;
+        uint32_t base;
+      } u_delta_d;
+      u_delta_d.real = this->delta_d;
+      *(outbuffer + offset + 0) = (u_delta_d.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_delta_d.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_delta_d.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_delta_d.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->delta_d);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->image.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_f;
+      u_f.base = 0;
+      u_f.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_f.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_f.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_f.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->f = u_f.real;
+      offset += sizeof(this->f);
+      union {
+        float real;
+        uint32_t base;
+      } u_T;
+      u_T.base = 0;
+      u_T.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_T.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_T.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_T.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->T = u_T.real;
+      offset += sizeof(this->T);
+      offset += this->valid_window.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_min_disparity;
+      u_min_disparity.base = 0;
+      u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->min_disparity = u_min_disparity.real;
+      offset += sizeof(this->min_disparity);
+      union {
+        float real;
+        uint32_t base;
+      } u_max_disparity;
+      u_max_disparity.base = 0;
+      u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->max_disparity = u_max_disparity.real;
+      offset += sizeof(this->max_disparity);
+      union {
+        float real;
+        uint32_t base;
+      } u_delta_d;
+      u_delta_d.base = 0;
+      u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->delta_d = u_delta_d.real;
+      offset += sizeof(this->delta_d);
+     return offset;
+    }
+
+    const char * getType(){ return "stereo_msgs/DisparityImage"; };
+    const char * getMD5(){ return "04a177815f75271039fa21f16acad8c9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf/FrameGraph.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/FrameGraph.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_FrameGraph_h
+#define _ROS_SERVICE_FrameGraph_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace tf
+{
+
+static const char FRAMEGRAPH[] = "tf/FrameGraph";
+
+  class FrameGraphRequest : public ros::Msg
+  {
+    public:
+
+    FrameGraphRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class FrameGraphResponse : public ros::Msg
+  {
+    public:
+      const char* dot_graph;
+
+    FrameGraphResponse():
+      dot_graph("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_dot_graph = strlen(this->dot_graph);
+      memcpy(outbuffer + offset, &length_dot_graph, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->dot_graph, length_dot_graph);
+      offset += length_dot_graph;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_dot_graph;
+      memcpy(&length_dot_graph, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_dot_graph; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_dot_graph-1]=0;
+      this->dot_graph = (char *)(inbuffer + offset-1);
+      offset += length_dot_graph;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+    const char * getMD5(){ return "c4af9ac907e58e906eb0b6e3c58478c0"; };
+
+  };
+
+  class FrameGraph {
+    public:
+    typedef FrameGraphRequest Request;
+    typedef FrameGraphResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 tf/tf.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tf.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,56 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_TF_H_
+#define ROS_TF_H_
+
+#include "geometry_msgs/TransformStamped.h"
+
+namespace tf
+{
+  
+  static inline geometry_msgs::Quaternion createQuaternionFromYaw(double yaw)
+  {
+    geometry_msgs::Quaternion q;
+    q.x = 0;
+    q.y = 0;
+    q.z = sin(yaw * 0.5);
+    q.w = cos(yaw * 0.5);
+    return q;
+  }
+
+}
+
+#endif
+
diff -r 000000000000 -r fd24f7ca9688 tf/tfMessage.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tfMessage.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_tf_tfMessage_h
+#define _ROS_tf_tfMessage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/TransformStamped.h"
+
+namespace tf
+{
+
+  class tfMessage : public ros::Msg
+  {
+    public:
+      uint8_t transforms_length;
+      geometry_msgs::TransformStamped st_transforms;
+      geometry_msgs::TransformStamped * transforms;
+
+    tfMessage():
+      transforms_length(0), transforms(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = transforms_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t transforms_lengthT = *(inbuffer + offset++);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
+      offset += 3;
+      transforms_length = transforms_lengthT;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->st_transforms.deserialize(inbuffer + offset);
+        memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "tf/tfMessage"; };
+    const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf/transform_broadcaster.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/transform_broadcaster.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,68 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_TRANSFORM_BROADCASTER_H_
+#define ROS_TRANSFORM_BROADCASTER_H_
+
+#include "tfMessage.h"
+
+namespace tf
+{
+
+  class TransformBroadcaster
+  {
+    public:
+      TransformBroadcaster() : publisher_("/tf", &internal_msg) {}
+
+      void init(ros::NodeHandle &nh)
+      {
+        nh.advertise(publisher_);
+      }
+
+      void sendTransform(geometry_msgs::TransformStamped &transform)
+      {
+        internal_msg.transforms_length = 1;
+        internal_msg.transforms = &transform;
+        publisher_.publish(&internal_msg);
+      }
+
+    private:
+      tf::tfMessage internal_msg;
+      ros::Publisher publisher_;
+  };
+
+}
+
+#endif
+
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/FrameGraph.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/FrameGraph.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_FrameGraph_h
+#define _ROS_SERVICE_FrameGraph_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace tf2_msgs
+{
+
+static const char FRAMEGRAPH[] = "tf2_msgs/FrameGraph";
+
+  class FrameGraphRequest : public ros::Msg
+  {
+    public:
+
+    FrameGraphRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class FrameGraphResponse : public ros::Msg
+  {
+    public:
+      const char* frame_yaml;
+
+    FrameGraphResponse():
+      frame_yaml("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_frame_yaml = strlen(this->frame_yaml);
+      memcpy(outbuffer + offset, &length_frame_yaml, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->frame_yaml, length_frame_yaml);
+      offset += length_frame_yaml;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_frame_yaml;
+      memcpy(&length_frame_yaml, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_frame_yaml; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_frame_yaml-1]=0;
+      this->frame_yaml = (char *)(inbuffer + offset-1);
+      offset += length_frame_yaml;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+    const char * getMD5(){ return "437ea58e9463815a0d511c7326b686b0"; };
+
+  };
+
+  class FrameGraph {
+    public:
+    typedef FrameGraphRequest Request;
+    typedef FrameGraphResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_tf2_msgs_LookupTransformAction_h
+#define _ROS_tf2_msgs_LookupTransformAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "tf2_msgs/LookupTransformActionGoal.h"
+#include "tf2_msgs/LookupTransformActionResult.h"
+#include "tf2_msgs/LookupTransformActionFeedback.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformAction : public ros::Msg
+  {
+    public:
+      tf2_msgs::LookupTransformActionGoal action_goal;
+      tf2_msgs::LookupTransformActionResult action_result;
+      tf2_msgs::LookupTransformActionFeedback action_feedback;
+
+    LookupTransformAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformAction"; };
+    const char * getMD5(){ return "7ee01ba91a56c2245c610992dbaa3c37"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_tf2_msgs_LookupTransformActionFeedback_h
+#define _ROS_tf2_msgs_LookupTransformActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "tf2_msgs/LookupTransformFeedback.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      tf2_msgs::LookupTransformFeedback feedback;
+
+    LookupTransformActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_tf2_msgs_LookupTransformActionGoal_h
+#define _ROS_tf2_msgs_LookupTransformActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "tf2_msgs/LookupTransformGoal.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      tf2_msgs::LookupTransformGoal goal;
+
+    LookupTransformActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformActionGoal"; };
+    const char * getMD5(){ return "f2e7bcdb75c847978d0351a13e699da5"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_tf2_msgs_LookupTransformActionResult_h
+#define _ROS_tf2_msgs_LookupTransformActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "tf2_msgs/LookupTransformResult.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      tf2_msgs::LookupTransformResult result;
+
+    LookupTransformActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformActionResult"; };
+    const char * getMD5(){ return "ac26ce75a41384fa8bb4dc10f491ab90"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_tf2_msgs_LookupTransformFeedback_h
+#define _ROS_tf2_msgs_LookupTransformFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformFeedback : public ros::Msg
+  {
+    public:
+
+    LookupTransformFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,171 @@
+#ifndef _ROS_tf2_msgs_LookupTransformGoal_h
+#define _ROS_tf2_msgs_LookupTransformGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+#include "ros/duration.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformGoal : public ros::Msg
+  {
+    public:
+      const char* target_frame;
+      const char* source_frame;
+      ros::Time source_time;
+      ros::Duration timeout;
+      ros::Time target_time;
+      const char* fixed_frame;
+      bool advanced;
+
+    LookupTransformGoal():
+      target_frame(""),
+      source_frame(""),
+      source_time(),
+      timeout(),
+      target_time(),
+      fixed_frame(""),
+      advanced(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_target_frame = strlen(this->target_frame);
+      memcpy(outbuffer + offset, &length_target_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->target_frame, length_target_frame);
+      offset += length_target_frame;
+      uint32_t length_source_frame = strlen(this->source_frame);
+      memcpy(outbuffer + offset, &length_source_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->source_frame, length_source_frame);
+      offset += length_source_frame;
+      *(outbuffer + offset + 0) = (this->source_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->source_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->source_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->source_time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->source_time.sec);
+      *(outbuffer + offset + 0) = (this->source_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->source_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->source_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->source_time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->source_time.nsec);
+      *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timeout.sec);
+      *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timeout.nsec);
+      *(outbuffer + offset + 0) = (this->target_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->target_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->target_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->target_time.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->target_time.sec);
+      *(outbuffer + offset + 0) = (this->target_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->target_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->target_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->target_time.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->target_time.nsec);
+      uint32_t length_fixed_frame = strlen(this->fixed_frame);
+      memcpy(outbuffer + offset, &length_fixed_frame, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->fixed_frame, length_fixed_frame);
+      offset += length_fixed_frame;
+      union {
+        bool real;
+        uint8_t base;
+      } u_advanced;
+      u_advanced.real = this->advanced;
+      *(outbuffer + offset + 0) = (u_advanced.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->advanced);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_target_frame;
+      memcpy(&length_target_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_target_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_target_frame-1]=0;
+      this->target_frame = (char *)(inbuffer + offset-1);
+      offset += length_target_frame;
+      uint32_t length_source_frame;
+      memcpy(&length_source_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_source_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_source_frame-1]=0;
+      this->source_frame = (char *)(inbuffer + offset-1);
+      offset += length_source_frame;
+      this->source_time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->source_time.sec);
+      this->source_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->source_time.nsec);
+      this->timeout.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timeout.sec);
+      this->timeout.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timeout.nsec);
+      this->target_time.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->target_time.sec);
+      this->target_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->target_time.nsec);
+      uint32_t length_fixed_frame;
+      memcpy(&length_fixed_frame, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_fixed_frame; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_fixed_frame-1]=0;
+      this->fixed_frame = (char *)(inbuffer + offset-1);
+      offset += length_fixed_frame;
+      union {
+        bool real;
+        uint8_t base;
+      } u_advanced;
+      u_advanced.base = 0;
+      u_advanced.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->advanced = u_advanced.real;
+      offset += sizeof(this->advanced);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformGoal"; };
+    const char * getMD5(){ return "35e3720468131d675a18bb6f3e5f22f8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/LookupTransformResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,48 @@
+#ifndef _ROS_tf2_msgs_LookupTransformResult_h
+#define _ROS_tf2_msgs_LookupTransformResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/TransformStamped.h"
+#include "tf2_msgs/TF2Error.h"
+
+namespace tf2_msgs
+{
+
+  class LookupTransformResult : public ros::Msg
+  {
+    public:
+      geometry_msgs::TransformStamped transform;
+      tf2_msgs::TF2Error error;
+
+    LookupTransformResult():
+      transform(),
+      error()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->transform.serialize(outbuffer + offset);
+      offset += this->error.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->transform.deserialize(inbuffer + offset);
+      offset += this->error.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/LookupTransformResult"; };
+    const char * getMD5(){ return "3fe5db6a19ca9cfb675418c5ad875c36"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/TF2Error.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/TF2Error.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,67 @@
+#ifndef _ROS_tf2_msgs_TF2Error_h
+#define _ROS_tf2_msgs_TF2Error_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace tf2_msgs
+{
+
+  class TF2Error : public ros::Msg
+  {
+    public:
+      uint8_t error;
+      const char* error_string;
+      enum { NO_ERROR =  0 };
+      enum { LOOKUP_ERROR =  1 };
+      enum { CONNECTIVITY_ERROR =  2 };
+      enum { EXTRAPOLATION_ERROR =  3 };
+      enum { INVALID_ARGUMENT_ERROR =  4 };
+      enum { TIMEOUT_ERROR =  5 };
+      enum { TRANSFORM_ERROR =  6 };
+
+    TF2Error():
+      error(0),
+      error_string("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->error >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->error);
+      uint32_t length_error_string = strlen(this->error_string);
+      memcpy(outbuffer + offset, &length_error_string, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->error_string, length_error_string);
+      offset += length_error_string;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->error =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->error);
+      uint32_t length_error_string;
+      memcpy(&length_error_string, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_error_string; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_error_string-1]=0;
+      this->error_string = (char *)(inbuffer + offset-1);
+      offset += length_error_string;
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/TF2Error"; };
+    const char * getMD5(){ return "bc6848fd6fd750c92e38575618a4917d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 tf2_msgs/TFMessage.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/TFMessage.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_tf2_msgs_TFMessage_h
+#define _ROS_tf2_msgs_TFMessage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/TransformStamped.h"
+
+namespace tf2_msgs
+{
+
+  class TFMessage : public ros::Msg
+  {
+    public:
+      uint8_t transforms_length;
+      geometry_msgs::TransformStamped st_transforms;
+      geometry_msgs::TransformStamped * transforms;
+
+    TFMessage():
+      transforms_length(0), transforms(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = transforms_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t transforms_lengthT = *(inbuffer + offset++);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
+      offset += 3;
+      transforms_length = transforms_lengthT;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->st_transforms.deserialize(inbuffer + offset);
+        memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "tf2_msgs/TFMessage"; };
+    const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 theora_image_transport/Packet.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/theora_image_transport/Packet.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,173 @@
+#ifndef _ROS_theora_image_transport_Packet_h
+#define _ROS_theora_image_transport_Packet_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace theora_image_transport
+{
+
+  class Packet : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+      int32_t b_o_s;
+      int32_t e_o_s;
+      int64_t granulepos;
+      int64_t packetno;
+
+    Packet():
+      header(),
+      data_length(0), data(NULL),
+      b_o_s(0),
+      e_o_s(0),
+      granulepos(0),
+      packetno(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_b_o_s;
+      u_b_o_s.real = this->b_o_s;
+      *(outbuffer + offset + 0) = (u_b_o_s.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b_o_s.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b_o_s.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b_o_s.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->b_o_s);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_e_o_s;
+      u_e_o_s.real = this->e_o_s;
+      *(outbuffer + offset + 0) = (u_e_o_s.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_e_o_s.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_e_o_s.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_e_o_s.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->e_o_s);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_granulepos;
+      u_granulepos.real = this->granulepos;
+      *(outbuffer + offset + 0) = (u_granulepos.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_granulepos.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_granulepos.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_granulepos.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_granulepos.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_granulepos.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_granulepos.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_granulepos.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->granulepos);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_packetno;
+      u_packetno.real = this->packetno;
+      *(outbuffer + offset + 0) = (u_packetno.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_packetno.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_packetno.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_packetno.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_packetno.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_packetno.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_packetno.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_packetno.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->packetno);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_b_o_s;
+      u_b_o_s.base = 0;
+      u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->b_o_s = u_b_o_s.real;
+      offset += sizeof(this->b_o_s);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_e_o_s;
+      u_e_o_s.base = 0;
+      u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->e_o_s = u_e_o_s.real;
+      offset += sizeof(this->e_o_s);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_granulepos;
+      u_granulepos.base = 0;
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->granulepos = u_granulepos.real;
+      offset += sizeof(this->granulepos);
+      union {
+        int64_t real;
+        uint64_t base;
+      } u_packetno;
+      u_packetno.base = 0;
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->packetno = u_packetno.real;
+      offset += sizeof(this->packetno);
+     return offset;
+    }
+
+    const char * getType(){ return "theora_image_transport/Packet"; };
+    const char * getMD5(){ return "33ac4e14a7cff32e7e0d65f18bb410f3"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 time.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/time.cpp	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,68 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include "ros/time.h"
+
+namespace ros
+{
+  void normalizeSecNSec(uint32_t& sec, uint32_t& nsec){
+    uint32_t nsec_part= nsec % 1000000000UL;
+    uint32_t sec_part = nsec / 1000000000UL;
+    sec += sec_part;
+    nsec = nsec_part;
+  }
+
+  Time& Time::fromNSec(int32_t t)
+  {
+    sec = t / 1000000000;
+    nsec = t % 1000000000;
+    normalizeSecNSec(sec, nsec);
+    return *this;
+  }
+
+  Time& Time::operator +=(const Duration &rhs)
+  {
+    sec += rhs.sec;
+    nsec += rhs.nsec;
+    normalizeSecNSec(sec, nsec);
+    return *this;
+  }
+
+  Time& Time::operator -=(const Duration &rhs){
+    sec += -rhs.sec;
+    nsec += -rhs.nsec;
+    normalizeSecNSec(sec, nsec);
+    return *this;
+  }
+}
diff -r 000000000000 -r fd24f7ca9688 topic_tools/DemuxAdd.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxAdd.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_DemuxAdd_h
+#define _ROS_SERVICE_DemuxAdd_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char DEMUXADD[] = "topic_tools/DemuxAdd";
+
+  class DemuxAddRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    DemuxAddRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXADD; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class DemuxAddResponse : public ros::Msg
+  {
+    public:
+
+    DemuxAddResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXADD; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class DemuxAdd {
+    public:
+    typedef DemuxAddRequest Request;
+    typedef DemuxAddResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/DemuxDelete.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxDelete.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_DemuxDelete_h
+#define _ROS_SERVICE_DemuxDelete_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char DEMUXDELETE[] = "topic_tools/DemuxDelete";
+
+  class DemuxDeleteRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    DemuxDeleteRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXDELETE; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class DemuxDeleteResponse : public ros::Msg
+  {
+    public:
+
+    DemuxDeleteResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXDELETE; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class DemuxDelete {
+    public:
+    typedef DemuxDeleteRequest Request;
+    typedef DemuxDeleteResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/DemuxList.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxList.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_DemuxList_h
+#define _ROS_SERVICE_DemuxList_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char DEMUXLIST[] = "topic_tools/DemuxList";
+
+  class DemuxListRequest : public ros::Msg
+  {
+    public:
+
+    DemuxListRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXLIST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class DemuxListResponse : public ros::Msg
+  {
+    public:
+      uint8_t topics_length;
+      char* st_topics;
+      char* * topics;
+
+    DemuxListResponse():
+      topics_length(0), topics(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = topics_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], length_topicsi);
+      offset += length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t topics_lengthT = *(inbuffer + offset++);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      offset += 3;
+      topics_length = topics_lengthT;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_topics; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_topics-1]=0;
+      this->st_topics = (char *)(inbuffer + offset-1);
+      offset += length_st_topics;
+        memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXLIST; };
+    const char * getMD5(){ return "b0eef9a05d4e829092fc2f2c3c2aad3d"; };
+
+  };
+
+  class DemuxList {
+    public:
+    typedef DemuxListRequest Request;
+    typedef DemuxListResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/DemuxSelect.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxSelect.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_DemuxSelect_h
+#define _ROS_SERVICE_DemuxSelect_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char DEMUXSELECT[] = "topic_tools/DemuxSelect";
+
+  class DemuxSelectRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    DemuxSelectRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXSELECT; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class DemuxSelectResponse : public ros::Msg
+  {
+    public:
+      const char* prev_topic;
+
+    DemuxSelectResponse():
+      prev_topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_prev_topic = strlen(this->prev_topic);
+      memcpy(outbuffer + offset, &length_prev_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->prev_topic, length_prev_topic);
+      offset += length_prev_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_prev_topic;
+      memcpy(&length_prev_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_prev_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_prev_topic-1]=0;
+      this->prev_topic = (char *)(inbuffer + offset-1);
+      offset += length_prev_topic;
+     return offset;
+    }
+
+    const char * getType(){ return DEMUXSELECT; };
+    const char * getMD5(){ return "3db0a473debdbafea387c9e49358c320"; };
+
+  };
+
+  class DemuxSelect {
+    public:
+    typedef DemuxSelectRequest Request;
+    typedef DemuxSelectResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/MuxAdd.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxAdd.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_MuxAdd_h
+#define _ROS_SERVICE_MuxAdd_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXADD[] = "topic_tools/MuxAdd";
+
+  class MuxAddRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    MuxAddRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return MUXADD; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxAddResponse : public ros::Msg
+  {
+    public:
+
+    MuxAddResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return MUXADD; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxAdd {
+    public:
+    typedef MuxAddRequest Request;
+    typedef MuxAddResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/MuxDelete.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxDelete.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_MuxDelete_h
+#define _ROS_SERVICE_MuxDelete_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXDELETE[] = "topic_tools/MuxDelete";
+
+  class MuxDeleteRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    MuxDeleteRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return MUXDELETE; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxDeleteResponse : public ros::Msg
+  {
+    public:
+
+    MuxDeleteResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return MUXDELETE; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxDelete {
+    public:
+    typedef MuxDeleteRequest Request;
+    typedef MuxDeleteResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/MuxList.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxList.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_MuxList_h
+#define _ROS_SERVICE_MuxList_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXLIST[] = "topic_tools/MuxList";
+
+  class MuxListRequest : public ros::Msg
+  {
+    public:
+
+    MuxListRequest()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return MUXLIST; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxListResponse : public ros::Msg
+  {
+    public:
+      uint8_t topics_length;
+      char* st_topics;
+      char* * topics;
+
+    MuxListResponse():
+      topics_length(0), topics(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = topics_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], length_topicsi);
+      offset += length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t topics_lengthT = *(inbuffer + offset++);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      offset += 3;
+      topics_length = topics_lengthT;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_topics; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_topics-1]=0;
+      this->st_topics = (char *)(inbuffer + offset-1);
+      offset += length_st_topics;
+        memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return MUXLIST; };
+    const char * getMD5(){ return "b0eef9a05d4e829092fc2f2c3c2aad3d"; };
+
+  };
+
+  class MuxList {
+    public:
+    typedef MuxListRequest Request;
+    typedef MuxListResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 topic_tools/MuxSelect.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxSelect.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,102 @@
+#ifndef _ROS_SERVICE_MuxSelect_h
+#define _ROS_SERVICE_MuxSelect_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXSELECT[] = "topic_tools/MuxSelect";
+
+  class MuxSelectRequest : public ros::Msg
+  {
+    public:
+      const char* topic;
+
+    MuxSelectRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic;
+      memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    const char * getType(){ return MUXSELECT; };
+    const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxSelectResponse : public ros::Msg
+  {
+    public:
+      const char* prev_topic;
+
+    MuxSelectResponse():
+      prev_topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_prev_topic = strlen(this->prev_topic);
+      memcpy(outbuffer + offset, &length_prev_topic, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->prev_topic, length_prev_topic);
+      offset += length_prev_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_prev_topic;
+      memcpy(&length_prev_topic, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_prev_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_prev_topic-1]=0;
+      this->prev_topic = (char *)(inbuffer + offset-1);
+      offset += length_prev_topic;
+     return offset;
+    }
+
+    const char * getType(){ return MUXSELECT; };
+    const char * getMD5(){ return "3db0a473debdbafea387c9e49358c320"; };
+
+  };
+
+  class MuxSelect {
+    public:
+    typedef MuxSelectRequest Request;
+    typedef MuxSelectResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 trajectory_msgs/JointTrajectory.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/JointTrajectory.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,96 @@
+#ifndef _ROS_trajectory_msgs_JointTrajectory_h
+#define _ROS_trajectory_msgs_JointTrajectory_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "trajectory_msgs/JointTrajectoryPoint.h"
+
+namespace trajectory_msgs
+{
+
+  class JointTrajectory : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      uint8_t points_length;
+      trajectory_msgs::JointTrajectoryPoint st_points;
+      trajectory_msgs::JointTrajectoryPoint * points;
+
+    JointTrajectory():
+      header(),
+      joint_names_length(0), joint_names(NULL),
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (trajectory_msgs::JointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::JointTrajectoryPoint));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::JointTrajectoryPoint));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "trajectory_msgs/JointTrajectory"; };
+    const char * getMD5(){ return "65b4f94a94d1ed67169da35a02f33d3f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 trajectory_msgs/JointTrajectoryPoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/JointTrajectoryPoint.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,249 @@
+#ifndef _ROS_trajectory_msgs_JointTrajectoryPoint_h
+#define _ROS_trajectory_msgs_JointTrajectoryPoint_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+
+namespace trajectory_msgs
+{
+
+  class JointTrajectoryPoint : public ros::Msg
+  {
+    public:
+      uint8_t positions_length;
+      double st_positions;
+      double * positions;
+      uint8_t velocities_length;
+      double st_velocities;
+      double * velocities;
+      uint8_t accelerations_length;
+      double st_accelerations;
+      double * accelerations;
+      uint8_t effort_length;
+      double st_effort;
+      double * effort;
+      ros::Duration time_from_start;
+
+    JointTrajectoryPoint():
+      positions_length(0), positions(NULL),
+      velocities_length(0), velocities(NULL),
+      accelerations_length(0), accelerations(NULL),
+      effort_length(0), effort(NULL),
+      time_from_start()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = positions_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < positions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_positionsi;
+      u_positionsi.real = this->positions[i];
+      *(outbuffer + offset + 0) = (u_positionsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_positionsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_positionsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_positionsi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_positionsi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_positionsi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_positionsi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_positionsi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->positions[i]);
+      }
+      *(outbuffer + offset++) = velocities_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < velocities_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_velocitiesi;
+      u_velocitiesi.real = this->velocities[i];
+      *(outbuffer + offset + 0) = (u_velocitiesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_velocitiesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_velocitiesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_velocitiesi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_velocitiesi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_velocitiesi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_velocitiesi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_velocitiesi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->velocities[i]);
+      }
+      *(outbuffer + offset++) = accelerations_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < accelerations_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_accelerationsi;
+      u_accelerationsi.real = this->accelerations[i];
+      *(outbuffer + offset + 0) = (u_accelerationsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_accelerationsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_accelerationsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_accelerationsi.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_accelerationsi.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_accelerationsi.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_accelerationsi.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_accelerationsi.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->accelerations[i]);
+      }
+      *(outbuffer + offset++) = effort_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < effort_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_efforti;
+      u_efforti.real = this->effort[i];
+      *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->effort[i]);
+      }
+      *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_from_start.sec);
+      *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_from_start.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t positions_lengthT = *(inbuffer + offset++);
+      if(positions_lengthT > positions_length)
+        this->positions = (double*)realloc(this->positions, positions_lengthT * sizeof(double));
+      offset += 3;
+      positions_length = positions_lengthT;
+      for( uint8_t i = 0; i < positions_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_positions;
+      u_st_positions.base = 0;
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_positions = u_st_positions.real;
+      offset += sizeof(this->st_positions);
+        memcpy( &(this->positions[i]), &(this->st_positions), sizeof(double));
+      }
+      uint8_t velocities_lengthT = *(inbuffer + offset++);
+      if(velocities_lengthT > velocities_length)
+        this->velocities = (double*)realloc(this->velocities, velocities_lengthT * sizeof(double));
+      offset += 3;
+      velocities_length = velocities_lengthT;
+      for( uint8_t i = 0; i < velocities_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_velocities;
+      u_st_velocities.base = 0;
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_velocities = u_st_velocities.real;
+      offset += sizeof(this->st_velocities);
+        memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(double));
+      }
+      uint8_t accelerations_lengthT = *(inbuffer + offset++);
+      if(accelerations_lengthT > accelerations_length)
+        this->accelerations = (double*)realloc(this->accelerations, accelerations_lengthT * sizeof(double));
+      offset += 3;
+      accelerations_length = accelerations_lengthT;
+      for( uint8_t i = 0; i < accelerations_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_accelerations;
+      u_st_accelerations.base = 0;
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_accelerations = u_st_accelerations.real;
+      offset += sizeof(this->st_accelerations);
+        memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(double));
+      }
+      uint8_t effort_lengthT = *(inbuffer + offset++);
+      if(effort_lengthT > effort_length)
+        this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
+      offset += 3;
+      effort_length = effort_lengthT;
+      for( uint8_t i = 0; i < effort_length; i++){
+      union {
+        double real;
+        uint64_t base;
+      } u_st_effort;
+      u_st_effort.base = 0;
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->st_effort = u_st_effort.real;
+      offset += sizeof(this->st_effort);
+        memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double));
+      }
+      this->time_from_start.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_from_start.sec);
+      this->time_from_start.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_from_start.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "trajectory_msgs/JointTrajectoryPoint"; };
+    const char * getMD5(){ return "f3cd1e1c4d320c79d6985c904ae5dcd3"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 trajectory_msgs/MultiDOFJointTrajectory.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/MultiDOFJointTrajectory.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,96 @@
+#ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
+#define _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "trajectory_msgs/MultiDOFJointTrajectoryPoint.h"
+
+namespace trajectory_msgs
+{
+
+  class MultiDOFJointTrajectory : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t joint_names_length;
+      char* st_joint_names;
+      char* * joint_names;
+      uint8_t points_length;
+      trajectory_msgs::MultiDOFJointTrajectoryPoint st_points;
+      trajectory_msgs::MultiDOFJointTrajectoryPoint * points;
+
+    MultiDOFJointTrajectory():
+      header(),
+      joint_names_length(0), joint_names(NULL),
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = joint_names_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t joint_names_lengthT = *(inbuffer + offset++);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      offset += 3;
+      joint_names_length = joint_names_lengthT;
+      for( uint8_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_joint_names-1]=0;
+      this->st_joint_names = (char *)(inbuffer + offset-1);
+      offset += length_st_joint_names;
+        memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
+      }
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (trajectory_msgs::MultiDOFJointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectory"; };
+    const char * getMD5(){ return "ef145a45a5f47b77b7f5cdde4b16c942"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 trajectory_msgs/MultiDOFJointTrajectoryPoint.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/MultiDOFJointTrajectoryPoint.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,123 @@
+#ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
+#define _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Transform.h"
+#include "geometry_msgs/Twist.h"
+#include "ros/duration.h"
+
+namespace trajectory_msgs
+{
+
+  class MultiDOFJointTrajectoryPoint : public ros::Msg
+  {
+    public:
+      uint8_t transforms_length;
+      geometry_msgs::Transform st_transforms;
+      geometry_msgs::Transform * transforms;
+      uint8_t velocities_length;
+      geometry_msgs::Twist st_velocities;
+      geometry_msgs::Twist * velocities;
+      uint8_t accelerations_length;
+      geometry_msgs::Twist st_accelerations;
+      geometry_msgs::Twist * accelerations;
+      ros::Duration time_from_start;
+
+    MultiDOFJointTrajectoryPoint():
+      transforms_length(0), transforms(NULL),
+      velocities_length(0), velocities(NULL),
+      accelerations_length(0), accelerations(NULL),
+      time_from_start()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = transforms_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = velocities_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < velocities_length; i++){
+      offset += this->velocities[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = accelerations_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < accelerations_length; i++){
+      offset += this->accelerations[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_from_start.sec);
+      *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_from_start.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t transforms_lengthT = *(inbuffer + offset++);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
+      offset += 3;
+      transforms_length = transforms_lengthT;
+      for( uint8_t i = 0; i < transforms_length; i++){
+      offset += this->st_transforms.deserialize(inbuffer + offset);
+        memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
+      }
+      uint8_t velocities_lengthT = *(inbuffer + offset++);
+      if(velocities_lengthT > velocities_length)
+        this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      velocities_length = velocities_lengthT;
+      for( uint8_t i = 0; i < velocities_length; i++){
+      offset += this->st_velocities.deserialize(inbuffer + offset);
+        memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist));
+      }
+      uint8_t accelerations_lengthT = *(inbuffer + offset++);
+      if(accelerations_lengthT > accelerations_length)
+        this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
+      offset += 3;
+      accelerations_length = accelerations_lengthT;
+      for( uint8_t i = 0; i < accelerations_length; i++){
+      offset += this->st_accelerations.deserialize(inbuffer + offset);
+        memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist));
+      }
+      this->time_from_start.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_from_start.sec);
+      this->time_from_start.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->time_from_start.nsec);
+     return offset;
+    }
+
+    const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; };
+    const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeAction.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeAction.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_turtle_actionlib_ShapeAction_h
+#define _ROS_turtle_actionlib_ShapeAction_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "turtle_actionlib/ShapeActionGoal.h"
+#include "turtle_actionlib/ShapeActionResult.h"
+#include "turtle_actionlib/ShapeActionFeedback.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeAction : public ros::Msg
+  {
+    public:
+      turtle_actionlib::ShapeActionGoal action_goal;
+      turtle_actionlib::ShapeActionResult action_result;
+      turtle_actionlib::ShapeActionFeedback action_feedback;
+
+    ShapeAction():
+      action_goal(),
+      action_result(),
+      action_feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->action_goal.serialize(outbuffer + offset);
+      offset += this->action_result.serialize(outbuffer + offset);
+      offset += this->action_feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->action_goal.deserialize(inbuffer + offset);
+      offset += this->action_result.deserialize(inbuffer + offset);
+      offset += this->action_feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeAction"; };
+    const char * getMD5(){ return "d73b17d6237a925511f5d7727a1dc903"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeActionFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_turtle_actionlib_ShapeActionFeedback_h
+#define _ROS_turtle_actionlib_ShapeActionFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "turtle_actionlib/ShapeFeedback.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeActionFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      turtle_actionlib::ShapeFeedback feedback;
+
+    ShapeActionFeedback():
+      header(),
+      status(),
+      feedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->feedback.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->feedback.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeActionFeedback"; };
+    const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeActionGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_turtle_actionlib_ShapeActionGoal_h
+#define _ROS_turtle_actionlib_ShapeActionGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalID.h"
+#include "turtle_actionlib/ShapeGoal.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeActionGoal : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalID goal_id;
+      turtle_actionlib::ShapeGoal goal;
+
+    ShapeActionGoal():
+      header(),
+      goal_id(),
+      goal()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->goal_id.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->goal_id.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeActionGoal"; };
+    const char * getMD5(){ return "dbfccd187f2ec9c593916447ffd6cc77"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeActionResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _ROS_turtle_actionlib_ShapeActionResult_h
+#define _ROS_turtle_actionlib_ShapeActionResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "actionlib_msgs/GoalStatus.h"
+#include "turtle_actionlib/ShapeResult.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeActionResult : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      actionlib_msgs::GoalStatus status;
+      turtle_actionlib::ShapeResult result;
+
+    ShapeActionResult():
+      header(),
+      status(),
+      result()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      offset += this->result.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      offset += this->result.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeActionResult"; };
+    const char * getMD5(){ return "c8d13d5d140f1047a2e4d3bf5c045822"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,38 @@
+#ifndef _ROS_turtle_actionlib_ShapeFeedback_h
+#define _ROS_turtle_actionlib_ShapeFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeFeedback : public ros::Msg
+  {
+    public:
+
+    ShapeFeedback()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeFeedback"; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeGoal.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeGoal.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,84 @@
+#ifndef _ROS_turtle_actionlib_ShapeGoal_h
+#define _ROS_turtle_actionlib_ShapeGoal_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeGoal : public ros::Msg
+  {
+    public:
+      int32_t edges;
+      float radius;
+
+    ShapeGoal():
+      edges(0),
+      radius(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_edges;
+      u_edges.real = this->edges;
+      *(outbuffer + offset + 0) = (u_edges.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_edges.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_edges.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_edges.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->edges);
+      union {
+        float real;
+        uint32_t base;
+      } u_radius;
+      u_radius.real = this->radius;
+      *(outbuffer + offset + 0) = (u_radius.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_radius.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_radius.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_radius.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->radius);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_edges;
+      u_edges.base = 0;
+      u_edges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_edges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_edges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_edges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->edges = u_edges.real;
+      offset += sizeof(this->edges);
+      union {
+        float real;
+        uint32_t base;
+      } u_radius;
+      u_radius.base = 0;
+      u_radius.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_radius.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_radius.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_radius.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->radius = u_radius.real;
+      offset += sizeof(this->radius);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeGoal"; };
+    const char * getMD5(){ return "3b9202ab7292cebe5a95ab2bf6b9c091"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/ShapeResult.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeResult.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,84 @@
+#ifndef _ROS_turtle_actionlib_ShapeResult_h
+#define _ROS_turtle_actionlib_ShapeResult_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtle_actionlib
+{
+
+  class ShapeResult : public ros::Msg
+  {
+    public:
+      float interior_angle;
+      float apothem;
+
+    ShapeResult():
+      interior_angle(0),
+      apothem(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_interior_angle;
+      u_interior_angle.real = this->interior_angle;
+      *(outbuffer + offset + 0) = (u_interior_angle.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_interior_angle.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_interior_angle.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_interior_angle.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->interior_angle);
+      union {
+        float real;
+        uint32_t base;
+      } u_apothem;
+      u_apothem.real = this->apothem;
+      *(outbuffer + offset + 0) = (u_apothem.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_apothem.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_apothem.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_apothem.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->apothem);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_interior_angle;
+      u_interior_angle.base = 0;
+      u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->interior_angle = u_interior_angle.real;
+      offset += sizeof(this->interior_angle);
+      union {
+        float real;
+        uint32_t base;
+      } u_apothem;
+      u_apothem.base = 0;
+      u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->apothem = u_apothem.real;
+      offset += sizeof(this->apothem);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/ShapeResult"; };
+    const char * getMD5(){ return "b06c6e2225f820dbc644270387cd1a7c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtle_actionlib/Velocity.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/Velocity.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,84 @@
+#ifndef _ROS_turtle_actionlib_Velocity_h
+#define _ROS_turtle_actionlib_Velocity_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtle_actionlib
+{
+
+  class Velocity : public ros::Msg
+  {
+    public:
+      float linear;
+      float angular;
+
+    Velocity():
+      linear(0),
+      angular(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_linear;
+      u_linear.real = this->linear;
+      *(outbuffer + offset + 0) = (u_linear.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_linear.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_linear.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_linear.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->linear);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular;
+      u_angular.real = this->angular;
+      *(outbuffer + offset + 0) = (u_angular.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angular.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angular.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angular.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angular);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_linear;
+      u_linear.base = 0;
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->linear = u_linear.real;
+      offset += sizeof(this->linear);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular;
+      u_angular.base = 0;
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angular = u_angular.real;
+      offset += sizeof(this->angular);
+     return offset;
+    }
+
+    const char * getType(){ return "turtle_actionlib/Velocity"; };
+    const char * getMD5(){ return "9d5c2dcd348ac8f76ce2a4307bd63a13"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtlesim/Color.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Color.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,56 @@
+#ifndef _ROS_turtlesim_Color_h
+#define _ROS_turtlesim_Color_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+  class Color : public ros::Msg
+  {
+    public:
+      uint8_t r;
+      uint8_t g;
+      uint8_t b;
+
+    Color():
+      r(0),
+      g(0),
+      b(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->r);
+      *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->g);
+      *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->b);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->r =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->r);
+      this->g =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->g);
+      this->b =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->b);
+     return offset;
+    }
+
+    const char * getType(){ return "turtlesim/Color"; };
+    const char * getMD5(){ return "353891e354491c51aabe32df673fb446"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtlesim/Kill.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Kill.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,86 @@
+#ifndef _ROS_SERVICE_Kill_h
+#define _ROS_SERVICE_Kill_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+static const char KILL[] = "turtlesim/Kill";
+
+  class KillRequest : public ros::Msg
+  {
+    public:
+      const char* name;
+
+    KillRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return KILL; };
+    const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
+
+  };
+
+  class KillResponse : public ros::Msg
+  {
+    public:
+
+    KillResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return KILL; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class Kill {
+    public:
+    typedef KillRequest Request;
+    typedef KillResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 turtlesim/Pose.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Pose.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,153 @@
+#ifndef _ROS_turtlesim_Pose_h
+#define _ROS_turtlesim_Pose_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+  class Pose : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float theta;
+      float linear_velocity;
+      float angular_velocity;
+
+    Pose():
+      x(0),
+      y(0),
+      theta(0),
+      linear_velocity(0),
+      angular_velocity(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.real = this->theta;
+      *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->theta);
+      union {
+        float real;
+        uint32_t base;
+      } u_linear_velocity;
+      u_linear_velocity.real = this->linear_velocity;
+      *(outbuffer + offset + 0) = (u_linear_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_linear_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_linear_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_linear_velocity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->linear_velocity);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular_velocity;
+      u_angular_velocity.real = this->angular_velocity;
+      *(outbuffer + offset + 0) = (u_angular_velocity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angular_velocity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angular_velocity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angular_velocity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angular_velocity);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.base = 0;
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->theta = u_theta.real;
+      offset += sizeof(this->theta);
+      union {
+        float real;
+        uint32_t base;
+      } u_linear_velocity;
+      u_linear_velocity.base = 0;
+      u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->linear_velocity = u_linear_velocity.real;
+      offset += sizeof(this->linear_velocity);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular_velocity;
+      u_angular_velocity.base = 0;
+      u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angular_velocity = u_angular_velocity.real;
+      offset += sizeof(this->angular_velocity);
+     return offset;
+    }
+
+    const char * getType(){ return "turtlesim/Pose"; };
+    const char * getMD5(){ return "863b248d5016ca62ea2e895ae5265cf9"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 turtlesim/SetPen.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/SetPen.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_SERVICE_SetPen_h
+#define _ROS_SERVICE_SetPen_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+static const char SETPEN[] = "turtlesim/SetPen";
+
+  class SetPenRequest : public ros::Msg
+  {
+    public:
+      uint8_t r;
+      uint8_t g;
+      uint8_t b;
+      uint8_t width;
+      uint8_t off;
+
+    SetPenRequest():
+      r(0),
+      g(0),
+      b(0),
+      width(0),
+      off(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->r);
+      *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->g);
+      *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->b);
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->width);
+      *(outbuffer + offset + 0) = (this->off >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->off);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->r =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->r);
+      this->g =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->g);
+      this->b =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->b);
+      this->width =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->width);
+      this->off =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->off);
+     return offset;
+    }
+
+    const char * getType(){ return SETPEN; };
+    const char * getMD5(){ return "9f452acce566bf0c0954594f69a8e41b"; };
+
+  };
+
+  class SetPenResponse : public ros::Msg
+  {
+    public:
+
+    SetPenResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SETPEN; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SetPen {
+    public:
+    typedef SetPenRequest Request;
+    typedef SetPenResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 turtlesim/Spawn.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Spawn.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,171 @@
+#ifndef _ROS_SERVICE_Spawn_h
+#define _ROS_SERVICE_Spawn_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+static const char SPAWN[] = "turtlesim/Spawn";
+
+  class SpawnRequest : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float theta;
+      const char* name;
+
+    SpawnRequest():
+      x(0),
+      y(0),
+      theta(0),
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.real = this->theta;
+      *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->theta);
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.base = 0;
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->theta = u_theta.real;
+      offset += sizeof(this->theta);
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return SPAWN; };
+    const char * getMD5(){ return "57f001c49ab7b11d699f8606c1f4f7ff"; };
+
+  };
+
+  class SpawnResponse : public ros::Msg
+  {
+    public:
+      const char* name;
+
+    SpawnResponse():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return SPAWN; };
+    const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
+
+  };
+
+  class Spawn {
+    public:
+    typedef SpawnRequest Request;
+    typedef SpawnResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 turtlesim/TeleportAbsolute.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/TeleportAbsolute.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,139 @@
+#ifndef _ROS_SERVICE_TeleportAbsolute_h
+#define _ROS_SERVICE_TeleportAbsolute_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+static const char TELEPORTABSOLUTE[] = "turtlesim/TeleportAbsolute";
+
+  class TeleportAbsoluteRequest : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float theta;
+
+    TeleportAbsoluteRequest():
+      x(0),
+      y(0),
+      theta(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.real = this->theta;
+      *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->theta);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        uint32_t base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        uint32_t base;
+      } u_theta;
+      u_theta.base = 0;
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->theta = u_theta.real;
+      offset += sizeof(this->theta);
+     return offset;
+    }
+
+    const char * getType(){ return TELEPORTABSOLUTE; };
+    const char * getMD5(){ return "a130bc60ee6513855dc62ea83fcc5b20"; };
+
+  };
+
+  class TeleportAbsoluteResponse : public ros::Msg
+  {
+    public:
+
+    TeleportAbsoluteResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return TELEPORTABSOLUTE; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class TeleportAbsolute {
+    public:
+    typedef TeleportAbsoluteRequest Request;
+    typedef TeleportAbsoluteResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 turtlesim/TeleportRelative.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/TeleportRelative.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,116 @@
+#ifndef _ROS_SERVICE_TeleportRelative_h
+#define _ROS_SERVICE_TeleportRelative_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace turtlesim
+{
+
+static const char TELEPORTRELATIVE[] = "turtlesim/TeleportRelative";
+
+  class TeleportRelativeRequest : public ros::Msg
+  {
+    public:
+      float linear;
+      float angular;
+
+    TeleportRelativeRequest():
+      linear(0),
+      angular(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_linear;
+      u_linear.real = this->linear;
+      *(outbuffer + offset + 0) = (u_linear.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_linear.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_linear.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_linear.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->linear);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular;
+      u_angular.real = this->angular;
+      *(outbuffer + offset + 0) = (u_angular.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angular.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angular.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angular.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angular);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_linear;
+      u_linear.base = 0;
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_linear.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->linear = u_linear.real;
+      offset += sizeof(this->linear);
+      union {
+        float real;
+        uint32_t base;
+      } u_angular;
+      u_angular.base = 0;
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angular.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angular = u_angular.real;
+      offset += sizeof(this->angular);
+     return offset;
+    }
+
+    const char * getType(){ return TELEPORTRELATIVE; };
+    const char * getMD5(){ return "9d5c2dcd348ac8f76ce2a4307bd63a13"; };
+
+  };
+
+  class TeleportRelativeResponse : public ros::Msg
+  {
+    public:
+
+    TeleportRelativeResponse()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return TELEPORTRELATIVE; };
+    const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class TeleportRelative {
+    public:
+    typedef TeleportRelativeRequest Request;
+    typedef TeleportRelativeResponse Response;
+  };
+
+}
+#endif
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/ImageMarker.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/ImageMarker.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,241 @@
+#ifndef _ROS_visualization_msgs_ImageMarker_h
+#define _ROS_visualization_msgs_ImageMarker_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point.h"
+#include "std_msgs/ColorRGBA.h"
+#include "ros/duration.h"
+
+namespace visualization_msgs
+{
+
+  class ImageMarker : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* ns;
+      int32_t id;
+      int32_t type;
+      int32_t action;
+      geometry_msgs::Point position;
+      float scale;
+      std_msgs::ColorRGBA outline_color;
+      uint8_t filled;
+      std_msgs::ColorRGBA fill_color;
+      ros::Duration lifetime;
+      uint8_t points_length;
+      geometry_msgs::Point st_points;
+      geometry_msgs::Point * points;
+      uint8_t outline_colors_length;
+      std_msgs::ColorRGBA st_outline_colors;
+      std_msgs::ColorRGBA * outline_colors;
+      enum { CIRCLE = 0 };
+      enum { LINE_STRIP = 1 };
+      enum { LINE_LIST = 2 };
+      enum { POLYGON = 3 };
+      enum { POINTS = 4 };
+      enum { ADD = 0 };
+      enum { REMOVE = 1 };
+
+    ImageMarker():
+      header(),
+      ns(""),
+      id(0),
+      type(0),
+      action(0),
+      position(),
+      scale(0),
+      outline_color(),
+      filled(0),
+      fill_color(),
+      lifetime(),
+      points_length(0), points(NULL),
+      outline_colors_length(0), outline_colors(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_ns = strlen(this->ns);
+      memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->ns, length_ns);
+      offset += length_ns;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.real = this->id;
+      *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_type;
+      u_type.real = this->type;
+      *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->type);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_action;
+      u_action.real = this->action;
+      *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->action);
+      offset += this->position.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_scale;
+      u_scale.real = this->scale;
+      *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->scale);
+      offset += this->outline_color.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->filled >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->filled);
+      offset += this->fill_color.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->lifetime.sec);
+      *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->lifetime.nsec);
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = outline_colors_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < outline_colors_length; i++){
+      offset += this->outline_colors[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_ns;
+      memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_ns; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_ns-1]=0;
+      this->ns = (char *)(inbuffer + offset-1);
+      offset += length_ns;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.base = 0;
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->id = u_id.real;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_type;
+      u_type.base = 0;
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->type = u_type.real;
+      offset += sizeof(this->type);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_action;
+      u_action.base = 0;
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->action = u_action.real;
+      offset += sizeof(this->action);
+      offset += this->position.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_scale;
+      u_scale.base = 0;
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->scale = u_scale.real;
+      offset += sizeof(this->scale);
+      offset += this->outline_color.deserialize(inbuffer + offset);
+      this->filled =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->filled);
+      offset += this->fill_color.deserialize(inbuffer + offset);
+      this->lifetime.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->lifetime.sec);
+      this->lifetime.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->lifetime.nsec);
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
+      }
+      uint8_t outline_colors_lengthT = *(inbuffer + offset++);
+      if(outline_colors_lengthT > outline_colors_length)
+        this->outline_colors = (std_msgs::ColorRGBA*)realloc(this->outline_colors, outline_colors_lengthT * sizeof(std_msgs::ColorRGBA));
+      offset += 3;
+      outline_colors_length = outline_colors_lengthT;
+      for( uint8_t i = 0; i < outline_colors_length; i++){
+      offset += this->st_outline_colors.deserialize(inbuffer + offset);
+        memcpy( &(this->outline_colors[i]), &(this->st_outline_colors), sizeof(std_msgs::ColorRGBA));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/ImageMarker"; };
+    const char * getMD5(){ return "1de93c67ec8858b831025a08fbf1b35c"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarker.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarker.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,145 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarker_h
+#define _ROS_visualization_msgs_InteractiveMarker_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+#include "visualization_msgs/MenuEntry.h"
+#include "visualization_msgs/InteractiveMarkerControl.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarker : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Pose pose;
+      const char* name;
+      const char* description;
+      float scale;
+      uint8_t menu_entries_length;
+      visualization_msgs::MenuEntry st_menu_entries;
+      visualization_msgs::MenuEntry * menu_entries;
+      uint8_t controls_length;
+      visualization_msgs::InteractiveMarkerControl st_controls;
+      visualization_msgs::InteractiveMarkerControl * controls;
+
+    InteractiveMarker():
+      header(),
+      pose(),
+      name(""),
+      description(""),
+      scale(0),
+      menu_entries_length(0), menu_entries(NULL),
+      controls_length(0), controls(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_description = strlen(this->description);
+      memcpy(outbuffer + offset, &length_description, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->description, length_description);
+      offset += length_description;
+      union {
+        float real;
+        uint32_t base;
+      } u_scale;
+      u_scale.real = this->scale;
+      *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->scale);
+      *(outbuffer + offset++) = menu_entries_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < menu_entries_length; i++){
+      offset += this->menu_entries[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = controls_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < controls_length; i++){
+      offset += this->controls[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_description;
+      memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_description; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_description-1]=0;
+      this->description = (char *)(inbuffer + offset-1);
+      offset += length_description;
+      union {
+        float real;
+        uint32_t base;
+      } u_scale;
+      u_scale.base = 0;
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->scale = u_scale.real;
+      offset += sizeof(this->scale);
+      uint8_t menu_entries_lengthT = *(inbuffer + offset++);
+      if(menu_entries_lengthT > menu_entries_length)
+        this->menu_entries = (visualization_msgs::MenuEntry*)realloc(this->menu_entries, menu_entries_lengthT * sizeof(visualization_msgs::MenuEntry));
+      offset += 3;
+      menu_entries_length = menu_entries_lengthT;
+      for( uint8_t i = 0; i < menu_entries_length; i++){
+      offset += this->st_menu_entries.deserialize(inbuffer + offset);
+        memcpy( &(this->menu_entries[i]), &(this->st_menu_entries), sizeof(visualization_msgs::MenuEntry));
+      }
+      uint8_t controls_lengthT = *(inbuffer + offset++);
+      if(controls_lengthT > controls_length)
+        this->controls = (visualization_msgs::InteractiveMarkerControl*)realloc(this->controls, controls_lengthT * sizeof(visualization_msgs::InteractiveMarkerControl));
+      offset += 3;
+      controls_length = controls_lengthT;
+      for( uint8_t i = 0; i < controls_length; i++){
+      offset += this->st_controls.deserialize(inbuffer + offset);
+        memcpy( &(this->controls[i]), &(this->st_controls), sizeof(visualization_msgs::InteractiveMarkerControl));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarker"; };
+    const char * getMD5(){ return "311bd5f6cd6a20820ac0ba84315f4e22"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarkerControl.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerControl.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,155 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarkerControl_h
+#define _ROS_visualization_msgs_InteractiveMarkerControl_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "geometry_msgs/Quaternion.h"
+#include "visualization_msgs/Marker.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarkerControl : public ros::Msg
+  {
+    public:
+      const char* name;
+      geometry_msgs::Quaternion orientation;
+      uint8_t orientation_mode;
+      uint8_t interaction_mode;
+      bool always_visible;
+      uint8_t markers_length;
+      visualization_msgs::Marker st_markers;
+      visualization_msgs::Marker * markers;
+      bool independent_marker_orientation;
+      const char* description;
+      enum { INHERIT =  0 };
+      enum { FIXED =  1 };
+      enum { VIEW_FACING =  2 };
+      enum { NONE =  0 };
+      enum { MENU =  1 };
+      enum { BUTTON =  2 };
+      enum { MOVE_AXIS =  3 };
+      enum { MOVE_PLANE =  4 };
+      enum { ROTATE_AXIS =  5 };
+      enum { MOVE_ROTATE =  6 };
+      enum { MOVE_3D =  7 };
+      enum { ROTATE_3D =  8 };
+      enum { MOVE_ROTATE_3D =  9 };
+
+    InteractiveMarkerControl():
+      name(""),
+      orientation(),
+      orientation_mode(0),
+      interaction_mode(0),
+      always_visible(0),
+      markers_length(0), markers(NULL),
+      independent_marker_orientation(0),
+      description("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      offset += this->orientation.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->orientation_mode);
+      *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->interaction_mode);
+      union {
+        bool real;
+        uint8_t base;
+      } u_always_visible;
+      u_always_visible.real = this->always_visible;
+      *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->always_visible);
+      *(outbuffer + offset++) = markers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->markers[i].serialize(outbuffer + offset);
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_independent_marker_orientation;
+      u_independent_marker_orientation.real = this->independent_marker_orientation;
+      *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->independent_marker_orientation);
+      uint32_t length_description = strlen(this->description);
+      memcpy(outbuffer + offset, &length_description, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->description, length_description);
+      offset += length_description;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      offset += this->orientation.deserialize(inbuffer + offset);
+      this->orientation_mode =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->orientation_mode);
+      this->interaction_mode =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->interaction_mode);
+      union {
+        bool real;
+        uint8_t base;
+      } u_always_visible;
+      u_always_visible.base = 0;
+      u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->always_visible = u_always_visible.real;
+      offset += sizeof(this->always_visible);
+      uint8_t markers_lengthT = *(inbuffer + offset++);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
+      offset += 3;
+      markers_length = markers_lengthT;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->st_markers.deserialize(inbuffer + offset);
+        memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker));
+      }
+      union {
+        bool real;
+        uint8_t base;
+      } u_independent_marker_orientation;
+      u_independent_marker_orientation.base = 0;
+      u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->independent_marker_orientation = u_independent_marker_orientation.real;
+      offset += sizeof(this->independent_marker_orientation);
+      uint32_t length_description;
+      memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_description; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_description-1]=0;
+      this->description = (char *)(inbuffer + offset-1);
+      offset += length_description;
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; };
+    const char * getMD5(){ return "e3a939c98cdd4f709d8e1dec2a9c3f37"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarkerFeedback.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerFeedback.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,142 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarkerFeedback_h
+#define _ROS_visualization_msgs_InteractiveMarkerFeedback_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Point.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarkerFeedback : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* client_id;
+      const char* marker_name;
+      const char* control_name;
+      uint8_t event_type;
+      geometry_msgs::Pose pose;
+      uint32_t menu_entry_id;
+      geometry_msgs::Point mouse_point;
+      bool mouse_point_valid;
+      enum { KEEP_ALIVE =  0 };
+      enum { POSE_UPDATE =  1 };
+      enum { MENU_SELECT =  2 };
+      enum { BUTTON_CLICK =  3 };
+      enum { MOUSE_DOWN =  4 };
+      enum { MOUSE_UP =  5 };
+
+    InteractiveMarkerFeedback():
+      header(),
+      client_id(""),
+      marker_name(""),
+      control_name(""),
+      event_type(0),
+      pose(),
+      menu_entry_id(0),
+      mouse_point(),
+      mouse_point_valid(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_client_id = strlen(this->client_id);
+      memcpy(outbuffer + offset, &length_client_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->client_id, length_client_id);
+      offset += length_client_id;
+      uint32_t length_marker_name = strlen(this->marker_name);
+      memcpy(outbuffer + offset, &length_marker_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->marker_name, length_marker_name);
+      offset += length_marker_name;
+      uint32_t length_control_name = strlen(this->control_name);
+      memcpy(outbuffer + offset, &length_control_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->control_name, length_control_name);
+      offset += length_control_name;
+      *(outbuffer + offset + 0) = (this->event_type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->event_type);
+      offset += this->pose.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->menu_entry_id >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->menu_entry_id >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->menu_entry_id >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->menu_entry_id >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->menu_entry_id);
+      offset += this->mouse_point.serialize(outbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_mouse_point_valid;
+      u_mouse_point_valid.real = this->mouse_point_valid;
+      *(outbuffer + offset + 0) = (u_mouse_point_valid.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->mouse_point_valid);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_client_id;
+      memcpy(&length_client_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_client_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_client_id-1]=0;
+      this->client_id = (char *)(inbuffer + offset-1);
+      offset += length_client_id;
+      uint32_t length_marker_name;
+      memcpy(&length_marker_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_marker_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_marker_name-1]=0;
+      this->marker_name = (char *)(inbuffer + offset-1);
+      offset += length_marker_name;
+      uint32_t length_control_name;
+      memcpy(&length_control_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_control_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_control_name-1]=0;
+      this->control_name = (char *)(inbuffer + offset-1);
+      offset += length_control_name;
+      this->event_type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->event_type);
+      offset += this->pose.deserialize(inbuffer + offset);
+      this->menu_entry_id =  ((uint32_t) (*(inbuffer + offset)));
+      this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->menu_entry_id);
+      offset += this->mouse_point.deserialize(inbuffer + offset);
+      union {
+        bool real;
+        uint8_t base;
+      } u_mouse_point_valid;
+      u_mouse_point_valid.base = 0;
+      u_mouse_point_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->mouse_point_valid = u_mouse_point_valid.real;
+      offset += sizeof(this->mouse_point_valid);
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarkerFeedback"; };
+    const char * getMD5(){ return "ab0f1eee058667e28c19ff3ffc3f4b78"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarkerInit.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerInit.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,98 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarkerInit_h
+#define _ROS_visualization_msgs_InteractiveMarkerInit_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "visualization_msgs/InteractiveMarker.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarkerInit : public ros::Msg
+  {
+    public:
+      const char* server_id;
+      uint64_t seq_num;
+      uint8_t markers_length;
+      visualization_msgs::InteractiveMarker st_markers;
+      visualization_msgs::InteractiveMarker * markers;
+
+    InteractiveMarkerInit():
+      server_id(""),
+      seq_num(0),
+      markers_length(0), markers(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_server_id = strlen(this->server_id);
+      memcpy(outbuffer + offset, &length_server_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->server_id, length_server_id);
+      offset += length_server_id;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_seq_num;
+      u_seq_num.real = this->seq_num;
+      *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->seq_num);
+      *(outbuffer + offset++) = markers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->markers[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_server_id;
+      memcpy(&length_server_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_server_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_server_id-1]=0;
+      this->server_id = (char *)(inbuffer + offset-1);
+      offset += length_server_id;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_seq_num;
+      u_seq_num.base = 0;
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->seq_num = u_seq_num.real;
+      offset += sizeof(this->seq_num);
+      uint8_t markers_lengthT = *(inbuffer + offset++);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker));
+      offset += 3;
+      markers_length = markers_lengthT;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->st_markers.deserialize(inbuffer + offset);
+        memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarkerInit"; };
+    const char * getMD5(){ return "aa2f1dcea79533d1710675195653028d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarkerPose.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerPose.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,64 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarkerPose_h
+#define _ROS_visualization_msgs_InteractiveMarkerPose_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarkerPose : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Pose pose;
+      const char* name;
+
+    InteractiveMarkerPose():
+      header(),
+      pose(),
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      uint32_t length_name = strlen(this->name);
+      memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+      uint32_t length_name;
+      memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarkerPose"; };
+    const char * getMD5(){ return "a6e6833209a196a38d798dadb02c81f8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/InteractiveMarkerUpdate.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerUpdate.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,159 @@
+#ifndef _ROS_visualization_msgs_InteractiveMarkerUpdate_h
+#define _ROS_visualization_msgs_InteractiveMarkerUpdate_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "visualization_msgs/InteractiveMarker.h"
+#include "visualization_msgs/InteractiveMarkerPose.h"
+
+namespace visualization_msgs
+{
+
+  class InteractiveMarkerUpdate : public ros::Msg
+  {
+    public:
+      const char* server_id;
+      uint64_t seq_num;
+      uint8_t type;
+      uint8_t markers_length;
+      visualization_msgs::InteractiveMarker st_markers;
+      visualization_msgs::InteractiveMarker * markers;
+      uint8_t poses_length;
+      visualization_msgs::InteractiveMarkerPose st_poses;
+      visualization_msgs::InteractiveMarkerPose * poses;
+      uint8_t erases_length;
+      char* st_erases;
+      char* * erases;
+      enum { KEEP_ALIVE =  0 };
+      enum { UPDATE =  1 };
+
+    InteractiveMarkerUpdate():
+      server_id(""),
+      seq_num(0),
+      type(0),
+      markers_length(0), markers(NULL),
+      poses_length(0), poses(NULL),
+      erases_length(0), erases(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_server_id = strlen(this->server_id);
+      memcpy(outbuffer + offset, &length_server_id, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->server_id, length_server_id);
+      offset += length_server_id;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_seq_num;
+      u_seq_num.real = this->seq_num;
+      *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->seq_num);
+      *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->type);
+      *(outbuffer + offset++) = markers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->markers[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = poses_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = erases_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < erases_length; i++){
+      uint32_t length_erasesi = strlen(this->erases[i]);
+      memcpy(outbuffer + offset, &length_erasesi, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->erases[i], length_erasesi);
+      offset += length_erasesi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_server_id;
+      memcpy(&length_server_id, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_server_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_server_id-1]=0;
+      this->server_id = (char *)(inbuffer + offset-1);
+      offset += length_server_id;
+      union {
+        uint64_t real;
+        uint32_t base;
+      } u_seq_num;
+      u_seq_num.base = 0;
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->seq_num = u_seq_num.real;
+      offset += sizeof(this->seq_num);
+      this->type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->type);
+      uint8_t markers_lengthT = *(inbuffer + offset++);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker));
+      offset += 3;
+      markers_length = markers_lengthT;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->st_markers.deserialize(inbuffer + offset);
+        memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker));
+      }
+      uint8_t poses_lengthT = *(inbuffer + offset++);
+      if(poses_lengthT > poses_length)
+        this->poses = (visualization_msgs::InteractiveMarkerPose*)realloc(this->poses, poses_lengthT * sizeof(visualization_msgs::InteractiveMarkerPose));
+      offset += 3;
+      poses_length = poses_lengthT;
+      for( uint8_t i = 0; i < poses_length; i++){
+      offset += this->st_poses.deserialize(inbuffer + offset);
+        memcpy( &(this->poses[i]), &(this->st_poses), sizeof(visualization_msgs::InteractiveMarkerPose));
+      }
+      uint8_t erases_lengthT = *(inbuffer + offset++);
+      if(erases_lengthT > erases_length)
+        this->erases = (char**)realloc(this->erases, erases_lengthT * sizeof(char*));
+      offset += 3;
+      erases_length = erases_lengthT;
+      for( uint8_t i = 0; i < erases_length; i++){
+      uint32_t length_st_erases;
+      memcpy(&length_st_erases, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_erases; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_erases-1]=0;
+      this->st_erases = (char *)(inbuffer + offset-1);
+      offset += length_st_erases;
+        memcpy( &(this->erases[i]), &(this->st_erases), sizeof(char*));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/InteractiveMarkerUpdate"; };
+    const char * getMD5(){ return "83e22f99d3b31fde725e0a338200e036"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/Marker.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/Marker.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,288 @@
+#ifndef _ROS_visualization_msgs_Marker_h
+#define _ROS_visualization_msgs_Marker_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+#include "geometry_msgs/Vector3.h"
+#include "std_msgs/ColorRGBA.h"
+#include "ros/duration.h"
+#include "geometry_msgs/Point.h"
+
+namespace visualization_msgs
+{
+
+  class Marker : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      const char* ns;
+      int32_t id;
+      int32_t type;
+      int32_t action;
+      geometry_msgs::Pose pose;
+      geometry_msgs::Vector3 scale;
+      std_msgs::ColorRGBA color;
+      ros::Duration lifetime;
+      bool frame_locked;
+      uint8_t points_length;
+      geometry_msgs::Point st_points;
+      geometry_msgs::Point * points;
+      uint8_t colors_length;
+      std_msgs::ColorRGBA st_colors;
+      std_msgs::ColorRGBA * colors;
+      const char* text;
+      const char* mesh_resource;
+      bool mesh_use_embedded_materials;
+      enum { ARROW = 0 };
+      enum { CUBE = 1 };
+      enum { SPHERE = 2 };
+      enum { CYLINDER = 3 };
+      enum { LINE_STRIP = 4 };
+      enum { LINE_LIST = 5 };
+      enum { CUBE_LIST = 6 };
+      enum { SPHERE_LIST = 7 };
+      enum { POINTS = 8 };
+      enum { TEXT_VIEW_FACING = 9 };
+      enum { MESH_RESOURCE = 10 };
+      enum { TRIANGLE_LIST = 11 };
+      enum { ADD = 0 };
+      enum { MODIFY = 0 };
+      enum { DELETE = 2 };
+
+    Marker():
+      header(),
+      ns(""),
+      id(0),
+      type(0),
+      action(0),
+      pose(),
+      scale(),
+      color(),
+      lifetime(),
+      frame_locked(0),
+      points_length(0), points(NULL),
+      colors_length(0), colors(NULL),
+      text(""),
+      mesh_resource(""),
+      mesh_use_embedded_materials(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      uint32_t length_ns = strlen(this->ns);
+      memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->ns, length_ns);
+      offset += length_ns;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.real = this->id;
+      *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_type;
+      u_type.real = this->type;
+      *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->type);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_action;
+      u_action.real = this->action;
+      *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->action);
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->scale.serialize(outbuffer + offset);
+      offset += this->color.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->lifetime.sec);
+      *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->lifetime.nsec);
+      union {
+        bool real;
+        uint8_t base;
+      } u_frame_locked;
+      u_frame_locked.real = this->frame_locked;
+      *(outbuffer + offset + 0) = (u_frame_locked.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->frame_locked);
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset++) = colors_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < colors_length; i++){
+      offset += this->colors[i].serialize(outbuffer + offset);
+      }
+      uint32_t length_text = strlen(this->text);
+      memcpy(outbuffer + offset, &length_text, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->text, length_text);
+      offset += length_text;
+      uint32_t length_mesh_resource = strlen(this->mesh_resource);
+      memcpy(outbuffer + offset, &length_mesh_resource, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->mesh_resource, length_mesh_resource);
+      offset += length_mesh_resource;
+      union {
+        bool real;
+        uint8_t base;
+      } u_mesh_use_embedded_materials;
+      u_mesh_use_embedded_materials.real = this->mesh_use_embedded_materials;
+      *(outbuffer + offset + 0) = (u_mesh_use_embedded_materials.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->mesh_use_embedded_materials);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_ns;
+      memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_ns; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_ns-1]=0;
+      this->ns = (char *)(inbuffer + offset-1);
+      offset += length_ns;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_id;
+      u_id.base = 0;
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->id = u_id.real;
+      offset += sizeof(this->id);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_type;
+      u_type.base = 0;
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->type = u_type.real;
+      offset += sizeof(this->type);
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_action;
+      u_action.base = 0;
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->action = u_action.real;
+      offset += sizeof(this->action);
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->scale.deserialize(inbuffer + offset);
+      offset += this->color.deserialize(inbuffer + offset);
+      this->lifetime.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->lifetime.sec);
+      this->lifetime.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->lifetime.nsec);
+      union {
+        bool real;
+        uint8_t base;
+      } u_frame_locked;
+      u_frame_locked.base = 0;
+      u_frame_locked.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->frame_locked = u_frame_locked.real;
+      offset += sizeof(this->frame_locked);
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
+      }
+      uint8_t colors_lengthT = *(inbuffer + offset++);
+      if(colors_lengthT > colors_length)
+        this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA));
+      offset += 3;
+      colors_length = colors_lengthT;
+      for( uint8_t i = 0; i < colors_length; i++){
+      offset += this->st_colors.deserialize(inbuffer + offset);
+        memcpy( &(this->colors[i]), &(this->st_colors), sizeof(std_msgs::ColorRGBA));
+      }
+      uint32_t length_text;
+      memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_text; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_text-1]=0;
+      this->text = (char *)(inbuffer + offset-1);
+      offset += length_text;
+      uint32_t length_mesh_resource;
+      memcpy(&length_mesh_resource, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_mesh_resource; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_mesh_resource-1]=0;
+      this->mesh_resource = (char *)(inbuffer + offset-1);
+      offset += length_mesh_resource;
+      union {
+        bool real;
+        uint8_t base;
+      } u_mesh_use_embedded_materials;
+      u_mesh_use_embedded_materials.base = 0;
+      u_mesh_use_embedded_materials.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->mesh_use_embedded_materials = u_mesh_use_embedded_materials.real;
+      offset += sizeof(this->mesh_use_embedded_materials);
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/Marker"; };
+    const char * getMD5(){ return "18326976df9d29249efc939e00342cde"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/MarkerArray.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/MarkerArray.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,59 @@
+#ifndef _ROS_visualization_msgs_MarkerArray_h
+#define _ROS_visualization_msgs_MarkerArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "visualization_msgs/Marker.h"
+
+namespace visualization_msgs
+{
+
+  class MarkerArray : public ros::Msg
+  {
+    public:
+      uint8_t markers_length;
+      visualization_msgs::Marker st_markers;
+      visualization_msgs::Marker * markers;
+
+    MarkerArray():
+      markers_length(0), markers(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = markers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->markers[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t markers_lengthT = *(inbuffer + offset++);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
+      offset += 3;
+      markers_length = markers_lengthT;
+      for( uint8_t i = 0; i < markers_length; i++){
+      offset += this->st_markers.deserialize(inbuffer + offset);
+        memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker));
+      }
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/MarkerArray"; };
+    const char * getMD5(){ return "90da67007c26525f655c1c269094e39f"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
diff -r 000000000000 -r fd24f7ca9688 visualization_msgs/MenuEntry.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/MenuEntry.h	Thu Mar 31 14:22:59 2016 +0000
@@ -0,0 +1,103 @@
+#ifndef _ROS_visualization_msgs_MenuEntry_h
+#define _ROS_visualization_msgs_MenuEntry_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace visualization_msgs
+{
+
+  class MenuEntry : public ros::Msg
+  {
+    public:
+      uint32_t id;
+      uint32_t parent_id;
+      const char* title;
+      const char* command;
+      uint8_t command_type;
+      enum { FEEDBACK = 0 };
+      enum { ROSRUN = 1 };
+      enum { ROSLAUNCH = 2 };
+
+    MenuEntry():
+      id(0),
+      parent_id(0),
+      title(""),
+      command(""),
+      command_type(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->id >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->id >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->id >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->id);
+      *(outbuffer + offset + 0) = (this->parent_id >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->parent_id >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->parent_id >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->parent_id >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->parent_id);
+      uint32_t length_title = strlen(this->title);
+      memcpy(outbuffer + offset, &length_title, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->title, length_title);
+      offset += length_title;
+      uint32_t length_command = strlen(this->command);
+      memcpy(outbuffer + offset, &length_command, sizeof(uint32_t));
+      offset += 4;
+      memcpy(outbuffer + offset, this->command, length_command);
+      offset += length_command;
+      *(outbuffer + offset + 0) = (this->command_type >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->command_type);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->id =  ((uint32_t) (*(inbuffer + offset)));
+      this->id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->id);
+      this->parent_id =  ((uint32_t) (*(inbuffer + offset)));
+      this->parent_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->parent_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->parent_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->parent_id);
+      uint32_t length_title;
+      memcpy(&length_title, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_title; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_title-1]=0;
+      this->title = (char *)(inbuffer + offset-1);
+      offset += length_title;
+      uint32_t length_command;
+      memcpy(&length_command, (inbuffer + offset), sizeof(uint32_t));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_command; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_command-1]=0;
+      this->command = (char *)(inbuffer + offset-1);
+      offset += length_command;
+      this->command_type =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->command_type);
+     return offset;
+    }
+
+    const char * getType(){ return "visualization_msgs/MenuEntry"; };
+    const char * getMD5(){ return "b90ec63024573de83b57aa93eb39be2d"; };
+
+  };
+
+}
+#endif
\ No newline at end of file