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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more

ROSSerial_mbed for Kinetic 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_kinetic

rosserial_mbed Hello World example for Kinetic Kame distribution

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:
Sat Dec 31 00:48:34 2016 +0000
Child:
1:a849bf78d77f
Commit message:
Initial commit, generated based on a clean kinetic-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/PidState.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/AddDiagnostics.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
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
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_arduino/Adc.h Show annotated file Show diff for this revision Revisions of this file
rosserial_arduino/Test.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/BatteryState.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/SetBool.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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/BufferedSerial.lib	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/sam_grove/code/BufferedSerial/#a0d37088b405
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MbedHardware.h	Sat Dec 31 00:48:34 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_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef actionlib::TestActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef actionlib::TestActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef actionlib::TestActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TestFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef actionlib::TestGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TestResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef actionlib::TestRequestActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef actionlib::TestRequestActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef actionlib::TestRequestActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TestRequestFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef actionlib::TestRequestGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TestRequestResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,215 @@
+#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:
+      typedef int32_t _terminate_status_type;
+      _terminate_status_type terminate_status;
+      typedef bool _ignore_cancel_type;
+      _ignore_cancel_type ignore_cancel;
+      typedef const char* _result_text_type;
+      _result_text_type result_text;
+      typedef int32_t _the_result_type;
+      _the_result_type the_result;
+      typedef bool _is_simple_client_type;
+      _is_simple_client_type is_simple_client;
+      typedef ros::Duration _delay_accept_type;
+      _delay_accept_type delay_accept;
+      typedef ros::Duration _delay_terminate_type;
+      _delay_terminate_type delay_terminate;
+      typedef ros::Duration _pause_status_type;
+      _pause_status_type 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);
+      varToArr(outbuffer + offset, length_result_text);
+      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;
+      arrToVar(length_result_text, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestRequestResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,80 @@
+#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:
+      typedef int32_t _the_result_type;
+      _the_result_type the_result;
+      typedef bool _is_simple_server_type;
+      _is_simple_server_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TestResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef actionlib::TwoIntsActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef actionlib::TwoIntsActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef actionlib::TwoIntsActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TwoIntsFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef actionlib::TwoIntsGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib::TwoIntsResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,102 @@
+#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:
+      typedef int64_t _a_type;
+      _a_type a;
+      typedef int64_t _b_type;
+      _b_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib/TwoIntsResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef int64_t _sum_type;
+      _sum_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalID.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef ros::Time _stamp_type;
+      _stamp_type stamp;
+      typedef const char* _id_type;
+      _id_type 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);
+      varToArr(outbuffer + offset, length_id);
+      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;
+      arrToVar(length_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalStatus.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,78 @@
+#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:
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef uint8_t _status_type;
+      _status_type status;
+      typedef const char* _text_type;
+      _text_type 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);
+      varToArr(outbuffer + offset, length_text);
+      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;
+      arrToVar(length_text, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_msgs/GoalStatusArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t status_list_length;
+      typedef actionlib_msgs::GoalStatus _status_list_type;
+      _status_list_type st_status_list;
+      _status_list_type * 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 + 0) = (this->status_list_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->status_list_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->status_list_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->status_list_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->status_list_length);
+      for( uint32_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);
+      uint32_t status_list_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->status_list_length);
+      if(status_list_lengthT > status_list_length)
+        this->status_list = (actionlib_msgs::GoalStatus*)realloc(this->status_list, status_list_lengthT * sizeof(actionlib_msgs::GoalStatus));
+      status_list_length = status_list_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef actionlib_tutorials::AveragingActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef actionlib_tutorials::AveragingActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef actionlib_tutorials::AveragingActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib_tutorials::AveragingFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef actionlib_tutorials::AveragingGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib_tutorials::AveragingResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef int32_t _sample_type;
+      _sample_type sample;
+      typedef float _data_type;
+      _data_type data;
+      typedef float _mean_type;
+      _mean_type mean;
+      typedef float _std_dev_type;
+      _std_dev_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _samples_type;
+      _samples_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/AveragingResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,86 @@
+#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:
+      typedef float _mean_type;
+      _mean_type mean;
+      typedef float _std_dev_type;
+      _std_dev_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef actionlib_tutorials::FibonacciActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef actionlib_tutorials::FibonacciActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef actionlib_tutorials::FibonacciActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib_tutorials::FibonacciFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef actionlib_tutorials::FibonacciGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef actionlib_tutorials::FibonacciResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      uint32_t sequence_length;
+      typedef int32_t _sequence_type;
+      _sequence_type st_sequence;
+      _sequence_type * sequence;
+
+    FibonacciFeedback():
+      sequence_length(0), sequence(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->sequence_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->sequence_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->sequence_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->sequence_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sequence_length);
+      for( uint32_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;
+      uint32_t sequence_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->sequence_length);
+      if(sequence_lengthT > sequence_length)
+        this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t));
+      sequence_length = sequence_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _order_type;
+      _order_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/actionlib_tutorials/FibonacciResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      uint32_t sequence_length;
+      typedef int32_t _sequence_type;
+      _sequence_type st_sequence;
+      _sequence_type * sequence;
+
+    FibonacciResult():
+      sequence_length(0), sequence(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->sequence_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->sequence_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->sequence_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->sequence_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->sequence_length);
+      for( uint32_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;
+      uint32_t sequence_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->sequence_length);
+      if(sequence_lengthT > sequence_length)
+        this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t));
+      sequence_length = sequence_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bond/Constants.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/bond/Status.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,144 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _id_type;
+      _id_type id;
+      typedef const char* _instance_id_type;
+      _instance_id_type instance_id;
+      typedef bool _active_type;
+      _active_type active;
+      typedef float _heartbeat_timeout_type;
+      _heartbeat_timeout_type heartbeat_timeout;
+      typedef float _heartbeat_period_type;
+      _heartbeat_period_type 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);
+      varToArr(outbuffer + offset, length_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->id, length_id);
+      offset += length_id;
+      uint32_t length_instance_id = strlen(this->instance_id);
+      varToArr(outbuffer + offset, length_instance_id);
+      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;
+      arrToVar(length_id, (inbuffer + offset));
+      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;
+      arrToVar(length_instance_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef control_msgs::FollowJointTrajectoryActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef control_msgs::FollowJointTrajectoryActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef control_msgs::FollowJointTrajectoryActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::FollowJointTrajectoryFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef control_msgs::FollowJointTrajectoryGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::FollowJointTrajectoryResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,97 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      typedef trajectory_msgs::JointTrajectoryPoint _desired_type;
+      _desired_type desired;
+      typedef trajectory_msgs::JointTrajectoryPoint _actual_type;
+      _actual_type actual;
+      typedef trajectory_msgs::JointTrajectoryPoint _error_type;
+      _error_type 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 + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      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);
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,119 @@
+#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:
+      typedef trajectory_msgs::JointTrajectory _trajectory_type;
+      _trajectory_type trajectory;
+      uint32_t path_tolerance_length;
+      typedef control_msgs::JointTolerance _path_tolerance_type;
+      _path_tolerance_type st_path_tolerance;
+      _path_tolerance_type * path_tolerance;
+      uint32_t goal_tolerance_length;
+      typedef control_msgs::JointTolerance _goal_tolerance_type;
+      _goal_tolerance_type st_goal_tolerance;
+      _goal_tolerance_type * goal_tolerance;
+      typedef ros::Duration _goal_time_tolerance_type;
+      _goal_time_tolerance_type 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 + 0) = (this->path_tolerance_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->path_tolerance_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->path_tolerance_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->path_tolerance_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->path_tolerance_length);
+      for( uint32_t i = 0; i < path_tolerance_length; i++){
+      offset += this->path_tolerance[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->goal_tolerance_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->goal_tolerance_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->goal_tolerance_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->goal_tolerance_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->goal_tolerance_length);
+      for( uint32_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);
+      uint32_t path_tolerance_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      path_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      path_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      path_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->path_tolerance_length);
+      if(path_tolerance_lengthT > path_tolerance_length)
+        this->path_tolerance = (control_msgs::JointTolerance*)realloc(this->path_tolerance, path_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
+      path_tolerance_length = path_tolerance_lengthT;
+      for( uint32_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));
+      }
+      uint32_t goal_tolerance_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      goal_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      goal_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      goal_tolerance_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->goal_tolerance_length);
+      if(goal_tolerance_lengthT > goal_tolerance_length)
+        this->goal_tolerance = (control_msgs::JointTolerance*)realloc(this->goal_tolerance, goal_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
+      goal_tolerance_length = goal_tolerance_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/FollowJointTrajectoryResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,85 @@
+#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:
+      typedef int32_t _error_code_type;
+      _error_code_type error_code;
+      typedef const char* _error_string_type;
+      _error_string_type 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);
+      varToArr(outbuffer + offset, length_error_string);
+      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;
+      arrToVar(length_error_string, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommand.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,102 @@
+#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:
+      typedef double _position_type;
+      _position_type position;
+      typedef double _max_effort_type;
+      _max_effort_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef control_msgs::GripperCommandActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef control_msgs::GripperCommandActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef control_msgs::GripperCommandActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::GripperCommandFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef control_msgs::GripperCommandGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::GripperCommandResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,138 @@
+#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:
+      typedef double _position_type;
+      _position_type position;
+      typedef double _effort_type;
+      _effort_type effort;
+      typedef bool _stalled_type;
+      _stalled_type stalled;
+      typedef bool _reached_goal_type;
+      _reached_goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,44 @@
+#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:
+      typedef control_msgs::GripperCommand _command_type;
+      _command_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/GripperCommandResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,138 @@
+#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:
+      typedef double _position_type;
+      _position_type position;
+      typedef double _effort_type;
+      _effort_type effort;
+      typedef bool _stalled_type;
+      _stalled_type stalled;
+      typedef bool _reached_goal_type;
+      _reached_goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointControllerState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,382 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _set_point_type;
+      _set_point_type set_point;
+      typedef double _process_value_type;
+      _process_value_type process_value;
+      typedef double _process_value_dot_type;
+      _process_value_dot_type process_value_dot;
+      typedef double _error_type;
+      _error_type error;
+      typedef double _time_step_type;
+      _time_step_type time_step;
+      typedef double _command_type;
+      _command_type command;
+      typedef double _p_type;
+      _p_type p;
+      typedef double _i_type;
+      _i_type i;
+      typedef double _d_type;
+      _d_type d;
+      typedef double _i_clamp_type;
+      _i_clamp_type i_clamp;
+      typedef bool _antiwindup_type;
+      _antiwindup_type antiwindup;
+
+    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),
+      antiwindup(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);
+      union {
+        bool real;
+        uint8_t base;
+      } u_antiwindup;
+      u_antiwindup.real = this->antiwindup;
+      *(outbuffer + offset + 0) = (u_antiwindup.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->antiwindup);
+      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);
+      union {
+        bool real;
+        uint8_t base;
+      } u_antiwindup;
+      u_antiwindup.base = 0;
+      u_antiwindup.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->antiwindup = u_antiwindup.real;
+      offset += sizeof(this->antiwindup);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/JointControllerState"; };
+    const char * getMD5(){ return "987ad85e4756f3aef7f1e5e7fe0595d1"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTolerance.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,151 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef double _position_type;
+      _position_type position;
+      typedef double _velocity_type;
+      _velocity_type velocity;
+      typedef double _acceleration_type;
+      _acceleration_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef control_msgs::JointTrajectoryActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef control_msgs::JointTrajectoryActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef control_msgs::JointTrajectoryActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::JointTrajectoryFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef control_msgs::JointTrajectoryGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::JointTrajectoryResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryControllerState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,97 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      typedef trajectory_msgs::JointTrajectoryPoint _desired_type;
+      _desired_type desired;
+      typedef trajectory_msgs::JointTrajectoryPoint _actual_type;
+      _actual_type actual;
+      typedef trajectory_msgs::JointTrajectoryPoint _error_type;
+      _error_type 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 + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      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);
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,44 @@
+#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:
+      typedef trajectory_msgs::JointTrajectory _trajectory_type;
+      _trajectory_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/JointTrajectoryResult.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PidState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,420 @@
+#ifndef _ROS_control_msgs_PidState_h
+#define _ROS_control_msgs_PidState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "ros/duration.h"
+
+namespace control_msgs
+{
+
+  class PidState : public ros::Msg
+  {
+    public:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef ros::Duration _timestep_type;
+      _timestep_type timestep;
+      typedef double _error_type;
+      _error_type error;
+      typedef double _error_dot_type;
+      _error_dot_type error_dot;
+      typedef double _p_error_type;
+      _p_error_type p_error;
+      typedef double _i_error_type;
+      _i_error_type i_error;
+      typedef double _d_error_type;
+      _d_error_type d_error;
+      typedef double _p_term_type;
+      _p_term_type p_term;
+      typedef double _i_term_type;
+      _i_term_type i_term;
+      typedef double _d_term_type;
+      _d_term_type d_term;
+      typedef double _i_max_type;
+      _i_max_type i_max;
+      typedef double _i_min_type;
+      _i_min_type i_min;
+      typedef double _output_type;
+      _output_type output;
+
+    PidState():
+      header(),
+      timestep(),
+      error(0),
+      error_dot(0),
+      p_error(0),
+      i_error(0),
+      d_error(0),
+      p_term(0),
+      i_term(0),
+      d_term(0),
+      i_max(0),
+      i_min(0),
+      output(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->timestep.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timestep.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timestep.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timestep.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timestep.sec);
+      *(outbuffer + offset + 0) = (this->timestep.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->timestep.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->timestep.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->timestep.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->timestep.nsec);
+      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_error_dot;
+      u_error_dot.real = this->error_dot;
+      *(outbuffer + offset + 0) = (u_error_dot.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_error_dot.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_error_dot.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_error_dot.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_error_dot.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_error_dot.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_error_dot.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_error_dot.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->error_dot);
+      union {
+        double real;
+        uint64_t base;
+      } u_p_error;
+      u_p_error.real = this->p_error;
+      *(outbuffer + offset + 0) = (u_p_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_p_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_p_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_p_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_p_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_p_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_p_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_p_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->p_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_error;
+      u_i_error.real = this->i_error;
+      *(outbuffer + offset + 0) = (u_i_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_d_error;
+      u_d_error.real = this->d_error;
+      *(outbuffer + offset + 0) = (u_d_error.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_d_error.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_d_error.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_d_error.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_d_error.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_d_error.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_d_error.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_d_error.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->d_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_p_term;
+      u_p_term.real = this->p_term;
+      *(outbuffer + offset + 0) = (u_p_term.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_p_term.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_p_term.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_p_term.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_p_term.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_p_term.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_p_term.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_p_term.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->p_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_term;
+      u_i_term.real = this->i_term;
+      *(outbuffer + offset + 0) = (u_i_term.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i_term.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i_term.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i_term.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i_term.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i_term.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i_term.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i_term.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_d_term;
+      u_d_term.real = this->d_term;
+      *(outbuffer + offset + 0) = (u_d_term.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_d_term.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_d_term.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_d_term.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_d_term.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_d_term.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_d_term.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_d_term.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->d_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_max;
+      u_i_max.real = this->i_max;
+      *(outbuffer + offset + 0) = (u_i_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i_max.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i_max.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i_max.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i_max.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i_max.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i_max);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_min;
+      u_i_min.real = this->i_min;
+      *(outbuffer + offset + 0) = (u_i_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_i_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_i_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_i_min.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_i_min.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_i_min.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_i_min.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_i_min.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->i_min);
+      union {
+        double real;
+        uint64_t base;
+      } u_output;
+      u_output.real = this->output;
+      *(outbuffer + offset + 0) = (u_output.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_output.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_output.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_output.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_output.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_output.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_output.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_output.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->output);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      this->timestep.sec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timestep.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timestep.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timestep.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timestep.sec);
+      this->timestep.nsec =  ((uint32_t) (*(inbuffer + offset)));
+      this->timestep.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->timestep.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->timestep.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->timestep.nsec);
+      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_error_dot;
+      u_error_dot.base = 0;
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_error_dot.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->error_dot = u_error_dot.real;
+      offset += sizeof(this->error_dot);
+      union {
+        double real;
+        uint64_t base;
+      } u_p_error;
+      u_p_error.base = 0;
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_p_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->p_error = u_p_error.real;
+      offset += sizeof(this->p_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_error;
+      u_i_error.base = 0;
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i_error = u_i_error.real;
+      offset += sizeof(this->i_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_d_error;
+      u_d_error.base = 0;
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_d_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->d_error = u_d_error.real;
+      offset += sizeof(this->d_error);
+      union {
+        double real;
+        uint64_t base;
+      } u_p_term;
+      u_p_term.base = 0;
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_p_term.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->p_term = u_p_term.real;
+      offset += sizeof(this->p_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_term;
+      u_i_term.base = 0;
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i_term.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i_term = u_i_term.real;
+      offset += sizeof(this->i_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_d_term;
+      u_d_term.base = 0;
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_d_term.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->d_term = u_d_term.real;
+      offset += sizeof(this->d_term);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_max;
+      u_i_max.base = 0;
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i_max.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i_max = u_i_max.real;
+      offset += sizeof(this->i_max);
+      union {
+        double real;
+        uint64_t base;
+      } u_i_min;
+      u_i_min.base = 0;
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_i_min.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->i_min = u_i_min.real;
+      offset += sizeof(this->i_min);
+      union {
+        double real;
+        uint64_t base;
+      } u_output;
+      u_output.base = 0;
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_output.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->output = u_output.real;
+      offset += sizeof(this->output);
+     return offset;
+    }
+
+    const char * getType(){ return "control_msgs/PidState"; };
+    const char * getMD5(){ return "b138ec00e886c10e73f27e8712252ea6"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef control_msgs::PointHeadActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef control_msgs::PointHeadActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef control_msgs::PointHeadActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::PointHeadFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef control_msgs::PointHeadGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::PointHeadResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef double _pointing_angle_error_type;
+      _pointing_angle_error_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,123 @@
+#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:
+      typedef geometry_msgs::PointStamped _target_type;
+      _target_type target;
+      typedef geometry_msgs::Vector3 _pointing_axis_type;
+      _pointing_axis_type pointing_axis;
+      typedef const char* _pointing_frame_type;
+      _pointing_frame_type pointing_frame;
+      typedef ros::Duration _min_duration_type;
+      _min_duration_type min_duration;
+      typedef double _max_velocity_type;
+      _max_velocity_type 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);
+      varToArr(outbuffer + offset, length_pointing_frame);
+      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;
+      arrToVar(length_pointing_frame, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/PointHeadResult.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/QueryCalibrationState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef bool _is_calibrated_type;
+      _is_calibrated_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/QueryTrajectoryState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,287 @@
+#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:
+      typedef ros::Time _time_type;
+      _time_type 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:
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t position_length;
+      typedef double _position_type;
+      _position_type st_position;
+      _position_type * position;
+      uint32_t velocity_length;
+      typedef double _velocity_type;
+      _velocity_type st_velocity;
+      _velocity_type * velocity;
+      uint32_t acceleration_length;
+      typedef double _acceleration_type;
+      _acceleration_type st_acceleration;
+      _acceleration_type * 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 + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->position_length);
+      for( uint32_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 + 0) = (this->velocity_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->velocity_length);
+      for( uint32_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 + 0) = (this->acceleration_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->acceleration_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->acceleration_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->acceleration_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->acceleration_length);
+      for( uint32_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;
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      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*));
+      }
+      uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->position_length);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      position_length = position_lengthT;
+      for( uint32_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));
+      }
+      uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->velocity_length);
+      if(velocity_lengthT > velocity_length)
+        this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
+      velocity_length = velocity_lengthT;
+      for( uint32_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));
+      }
+      uint32_t acceleration_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->acceleration_length);
+      if(acceleration_lengthT > acceleration_length)
+        this->acceleration = (double*)realloc(this->acceleration, acceleration_lengthT * sizeof(double));
+      acceleration_length = acceleration_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef control_msgs::SingleJointPositionActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef control_msgs::SingleJointPositionActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef control_msgs::SingleJointPositionActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::SingleJointPositionFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef control_msgs::SingleJointPositionGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef control_msgs::SingleJointPositionResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,140 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _position_type;
+      _position_type position;
+      typedef double _velocity_type;
+      _velocity_type velocity;
+      typedef double _error_type;
+      _error_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,126 @@
+#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:
+      typedef double _position_type;
+      _position_type position;
+      typedef ros::Duration _min_duration_type;
+      _min_duration_type min_duration;
+      typedef double _max_velocity_type;
+      _max_velocity_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/control_msgs/SingleJointPositionResult.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/AddDiagnostics.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,122 @@
+#ifndef _ROS_SERVICE_AddDiagnostics_h
+#define _ROS_SERVICE_AddDiagnostics_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace diagnostic_msgs
+{
+
+static const char ADDDIAGNOSTICS[] = "diagnostic_msgs/AddDiagnostics";
+
+  class AddDiagnosticsRequest : public ros::Msg
+  {
+    public:
+      typedef const char* _load_namespace_type;
+      _load_namespace_type load_namespace;
+
+    AddDiagnosticsRequest():
+      load_namespace("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_load_namespace = strlen(this->load_namespace);
+      varToArr(outbuffer + offset, length_load_namespace);
+      offset += 4;
+      memcpy(outbuffer + offset, this->load_namespace, length_load_namespace);
+      offset += length_load_namespace;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_load_namespace;
+      arrToVar(length_load_namespace, (inbuffer + offset));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_load_namespace; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_load_namespace-1]=0;
+      this->load_namespace = (char *)(inbuffer + offset-1);
+      offset += length_load_namespace;
+     return offset;
+    }
+
+    const char * getType(){ return ADDDIAGNOSTICS; };
+    const char * getMD5(){ return "c26cf6e164288fbc6050d74f838bcdf0"; };
+
+  };
+
+  class AddDiagnosticsResponse : public ros::Msg
+  {
+    public:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _message_type;
+      _message_type message;
+
+    AddDiagnosticsResponse():
+      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);
+      varToArr(outbuffer + offset, length_message);
+      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;
+      arrToVar(length_message, (inbuffer + offset));
+      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 ADDDIAGNOSTICS; };
+    const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; };
+
+  };
+
+  class AddDiagnostics {
+    public:
+    typedef AddDiagnosticsRequest Request;
+    typedef AddDiagnosticsResponse Response;
+  };
+
+}
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/DiagnosticArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t status_length;
+      typedef diagnostic_msgs::DiagnosticStatus _status_type;
+      _status_type st_status;
+      _status_type * 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 + 0) = (this->status_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->status_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->status_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->status_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->status_length);
+      for( uint32_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);
+      uint32_t status_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->status_length);
+      if(status_lengthT > status_length)
+        this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
+      status_length = status_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/DiagnosticStatus.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,137 @@
+#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:
+      typedef int8_t _level_type;
+      _level_type level;
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _message_type;
+      _message_type message;
+      typedef const char* _hardware_id_type;
+      _hardware_id_type hardware_id;
+      uint32_t values_length;
+      typedef diagnostic_msgs::KeyValue _values_type;
+      _values_type st_values;
+      _values_type * 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_message = strlen(this->message);
+      varToArr(outbuffer + offset, length_message);
+      offset += 4;
+      memcpy(outbuffer + offset, this->message, length_message);
+      offset += length_message;
+      uint32_t length_hardware_id = strlen(this->hardware_id);
+      varToArr(outbuffer + offset, length_hardware_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->hardware_id, length_hardware_id);
+      offset += length_hardware_id;
+      *(outbuffer + offset + 0) = (this->values_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->values_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->values_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->values_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values_length);
+      for( uint32_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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_message, (inbuffer + offset));
+      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;
+      arrToVar(length_hardware_id, (inbuffer + offset));
+      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;
+      uint32_t values_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->values_length);
+      if(values_lengthT > values_length)
+        this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue));
+      values_length = values_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/KeyValue.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,72 @@
+#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:
+      typedef const char* _key_type;
+      _key_type key;
+      typedef const char* _value_type;
+      _value_type value;
+
+    KeyValue():
+      key(""),
+      value("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_key = strlen(this->key);
+      varToArr(outbuffer + offset, length_key);
+      offset += 4;
+      memcpy(outbuffer + offset, this->key, length_key);
+      offset += length_key;
+      uint32_t length_value = strlen(this->value);
+      varToArr(outbuffer + offset, length_value);
+      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;
+      arrToVar(length_key, (inbuffer + offset));
+      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;
+      arrToVar(length_value, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/diagnostic_msgs/SelfTest.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,131 @@
+#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:
+      typedef const char* _id_type;
+      _id_type id;
+      typedef int8_t _passed_type;
+      _passed_type passed;
+      uint32_t status_length;
+      typedef diagnostic_msgs::DiagnosticStatus _status_type;
+      _status_type st_status;
+      _status_type * 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);
+      varToArr(outbuffer + offset, length_id);
+      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 + 0) = (this->status_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->status_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->status_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->status_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->status_length);
+      for( uint32_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;
+      arrToVar(length_id, (inbuffer + offset));
+      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);
+      uint32_t status_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      status_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->status_length);
+      if(status_lengthT > status_length)
+        this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
+      status_length = status_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/duration.cpp	Sat Dec 31 00:48:34 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;
+  }
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/BoolParameter.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,73 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef bool _value_type;
+      _value_type value;
+
+    BoolParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Config.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,168 @@
+#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:
+      uint32_t bools_length;
+      typedef dynamic_reconfigure::BoolParameter _bools_type;
+      _bools_type st_bools;
+      _bools_type * bools;
+      uint32_t ints_length;
+      typedef dynamic_reconfigure::IntParameter _ints_type;
+      _ints_type st_ints;
+      _ints_type * ints;
+      uint32_t strs_length;
+      typedef dynamic_reconfigure::StrParameter _strs_type;
+      _strs_type st_strs;
+      _strs_type * strs;
+      uint32_t doubles_length;
+      typedef dynamic_reconfigure::DoubleParameter _doubles_type;
+      _doubles_type st_doubles;
+      _doubles_type * doubles;
+      uint32_t groups_length;
+      typedef dynamic_reconfigure::GroupState _groups_type;
+      _groups_type st_groups;
+      _groups_type * 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 + 0) = (this->bools_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->bools_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->bools_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->bools_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->bools_length);
+      for( uint32_t i = 0; i < bools_length; i++){
+      offset += this->bools[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->ints_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->ints_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->ints_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->ints_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ints_length);
+      for( uint32_t i = 0; i < ints_length; i++){
+      offset += this->ints[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->strs_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->strs_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->strs_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->strs_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->strs_length);
+      for( uint32_t i = 0; i < strs_length; i++){
+      offset += this->strs[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->doubles_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->doubles_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->doubles_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->doubles_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->doubles_length);
+      for( uint32_t i = 0; i < doubles_length; i++){
+      offset += this->doubles[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->groups_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->groups_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->groups_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->groups_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->groups_length);
+      for( uint32_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;
+      uint32_t bools_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      bools_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      bools_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      bools_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->bools_length);
+      if(bools_lengthT > bools_length)
+        this->bools = (dynamic_reconfigure::BoolParameter*)realloc(this->bools, bools_lengthT * sizeof(dynamic_reconfigure::BoolParameter));
+      bools_length = bools_lengthT;
+      for( uint32_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));
+      }
+      uint32_t ints_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->ints_length);
+      if(ints_lengthT > ints_length)
+        this->ints = (dynamic_reconfigure::IntParameter*)realloc(this->ints, ints_lengthT * sizeof(dynamic_reconfigure::IntParameter));
+      ints_length = ints_lengthT;
+      for( uint32_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));
+      }
+      uint32_t strs_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      strs_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      strs_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      strs_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->strs_length);
+      if(strs_lengthT > strs_length)
+        this->strs = (dynamic_reconfigure::StrParameter*)realloc(this->strs, strs_lengthT * sizeof(dynamic_reconfigure::StrParameter));
+      strs_length = strs_lengthT;
+      for( uint32_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));
+      }
+      uint32_t doubles_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      doubles_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      doubles_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      doubles_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->doubles_length);
+      if(doubles_lengthT > doubles_length)
+        this->doubles = (dynamic_reconfigure::DoubleParameter*)realloc(this->doubles, doubles_lengthT * sizeof(dynamic_reconfigure::DoubleParameter));
+      doubles_length = doubles_lengthT;
+      for( uint32_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));
+      }
+      uint32_t groups_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->groups_length);
+      if(groups_lengthT > groups_length)
+        this->groups = (dynamic_reconfigure::GroupState*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::GroupState));
+      groups_length = groups_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/ConfigDescription.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,80 @@
+#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:
+      uint32_t groups_length;
+      typedef dynamic_reconfigure::Group _groups_type;
+      _groups_type st_groups;
+      _groups_type * groups;
+      typedef dynamic_reconfigure::Config _max_type;
+      _max_type max;
+      typedef dynamic_reconfigure::Config _min_type;
+      _min_type min;
+      typedef dynamic_reconfigure::Config _dflt_type;
+      _dflt_type dflt;
+
+    ConfigDescription():
+      groups_length(0), groups(NULL),
+      max(),
+      min(),
+      dflt()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->groups_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->groups_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->groups_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->groups_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->groups_length);
+      for( uint32_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;
+      uint32_t groups_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      groups_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->groups_length);
+      if(groups_lengthT > groups_length)
+        this->groups = (dynamic_reconfigure::Group*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::Group));
+      groups_length = groups_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/DoubleParameter.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef double _value_type;
+      _value_type value;
+
+    DoubleParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Group.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,146 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _type_type;
+      _type_type type;
+      uint32_t parameters_length;
+      typedef dynamic_reconfigure::ParamDescription _parameters_type;
+      _parameters_type st_parameters;
+      _parameters_type * parameters;
+      typedef int32_t _parent_type;
+      _parent_type parent;
+      typedef int32_t _id_type;
+      _id_type 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      varToArr(outbuffer + offset, length_type);
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      *(outbuffer + offset + 0) = (this->parameters_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->parameters_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->parameters_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->parameters_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->parameters_length);
+      for( uint32_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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_type, (inbuffer + offset));
+      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;
+      uint32_t parameters_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      parameters_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      parameters_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      parameters_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->parameters_length);
+      if(parameters_lengthT > parameters_length)
+        this->parameters = (dynamic_reconfigure::ParamDescription*)realloc(this->parameters, parameters_lengthT * sizeof(dynamic_reconfigure::ParamDescription));
+      parameters_length = parameters_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/GroupState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,121 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef bool _state_type;
+      _state_type state;
+      typedef int32_t _id_type;
+      _id_type id;
+      typedef int32_t _parent_type;
+      _parent_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/IntParameter.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef int32_t _value_type;
+      _value_type value;
+
+    IntParameter():
+      name(""),
+      value(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/ParamDescription.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,119 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _type_type;
+      _type_type type;
+      typedef uint32_t _level_type;
+      _level_type level;
+      typedef const char* _description_type;
+      _description_type description;
+      typedef const char* _edit_method_type;
+      _edit_method_type 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      varToArr(outbuffer + offset, length_type);
+      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);
+      varToArr(outbuffer + offset, length_description);
+      offset += 4;
+      memcpy(outbuffer + offset, this->description, length_description);
+      offset += length_description;
+      uint32_t length_edit_method = strlen(this->edit_method);
+      varToArr(outbuffer + offset, length_edit_method);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_type, (inbuffer + offset));
+      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;
+      arrToVar(length_description, (inbuffer + offset));
+      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;
+      arrToVar(length_edit_method, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/Reconfigure.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,81 @@
+#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:
+      typedef dynamic_reconfigure::Config _config_type;
+      _config_type 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:
+      typedef dynamic_reconfigure::Config _config_type;
+      _config_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/SensorLevels.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dynamic_reconfigure/StrParameter.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,72 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _value_type;
+      _value_type value;
+
+    StrParameter():
+      name(""),
+      value("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_value = strlen(this->value);
+      varToArr(outbuffer + offset, length_value);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_value, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ApplyBodyWrench.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,199 @@
+#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:
+      typedef const char* _body_name_type;
+      _body_name_type body_name;
+      typedef const char* _reference_frame_type;
+      _reference_frame_type reference_frame;
+      typedef geometry_msgs::Point _reference_point_type;
+      _reference_point_type reference_point;
+      typedef geometry_msgs::Wrench _wrench_type;
+      _wrench_type wrench;
+      typedef ros::Time _start_time_type;
+      _start_time_type start_time;
+      typedef ros::Duration _duration_type;
+      _duration_type 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);
+      varToArr(outbuffer + offset, length_body_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->body_name, length_body_name);
+      offset += length_body_name;
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      varToArr(outbuffer + offset, length_reference_frame);
+      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;
+      arrToVar(length_body_name, (inbuffer + offset));
+      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;
+      arrToVar(length_reference_frame, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ApplyJointEffort.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,202 @@
+#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:
+      typedef const char* _joint_name_type;
+      _joint_name_type joint_name;
+      typedef double _effort_type;
+      _effort_type effort;
+      typedef ros::Time _start_time_type;
+      _start_time_type start_time;
+      typedef ros::Duration _duration_type;
+      _duration_type 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);
+      varToArr(outbuffer + offset, length_joint_name);
+      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;
+      arrToVar(length_joint_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/BodyRequest.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _body_name_type;
+      _body_name_type body_name;
+
+    BodyRequestRequest():
+      body_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_body_name = strlen(this->body_name);
+      varToArr(outbuffer + offset, length_body_name);
+      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;
+      arrToVar(length_body_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ContactState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,223 @@
+#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:
+      typedef const char* _info_type;
+      _info_type info;
+      typedef const char* _collision1_name_type;
+      _collision1_name_type collision1_name;
+      typedef const char* _collision2_name_type;
+      _collision2_name_type collision2_name;
+      uint32_t wrenches_length;
+      typedef geometry_msgs::Wrench _wrenches_type;
+      _wrenches_type st_wrenches;
+      _wrenches_type * wrenches;
+      typedef geometry_msgs::Wrench _total_wrench_type;
+      _total_wrench_type total_wrench;
+      uint32_t contact_positions_length;
+      typedef geometry_msgs::Vector3 _contact_positions_type;
+      _contact_positions_type st_contact_positions;
+      _contact_positions_type * contact_positions;
+      uint32_t contact_normals_length;
+      typedef geometry_msgs::Vector3 _contact_normals_type;
+      _contact_normals_type st_contact_normals;
+      _contact_normals_type * contact_normals;
+      uint32_t depths_length;
+      typedef double _depths_type;
+      _depths_type st_depths;
+      _depths_type * 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);
+      varToArr(outbuffer + offset, length_info);
+      offset += 4;
+      memcpy(outbuffer + offset, this->info, length_info);
+      offset += length_info;
+      uint32_t length_collision1_name = strlen(this->collision1_name);
+      varToArr(outbuffer + offset, length_collision1_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->collision1_name, length_collision1_name);
+      offset += length_collision1_name;
+      uint32_t length_collision2_name = strlen(this->collision2_name);
+      varToArr(outbuffer + offset, length_collision2_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->collision2_name, length_collision2_name);
+      offset += length_collision2_name;
+      *(outbuffer + offset + 0) = (this->wrenches_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->wrenches_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->wrenches_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->wrenches_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->wrenches_length);
+      for( uint32_t i = 0; i < wrenches_length; i++){
+      offset += this->wrenches[i].serialize(outbuffer + offset);
+      }
+      offset += this->total_wrench.serialize(outbuffer + offset);
+      *(outbuffer + offset + 0) = (this->contact_positions_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->contact_positions_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->contact_positions_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->contact_positions_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->contact_positions_length);
+      for( uint32_t i = 0; i < contact_positions_length; i++){
+      offset += this->contact_positions[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->contact_normals_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->contact_normals_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->contact_normals_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->contact_normals_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->contact_normals_length);
+      for( uint32_t i = 0; i < contact_normals_length; i++){
+      offset += this->contact_normals[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->depths_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->depths_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->depths_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->depths_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->depths_length);
+      for( uint32_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;
+      arrToVar(length_info, (inbuffer + offset));
+      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;
+      arrToVar(length_collision1_name, (inbuffer + offset));
+      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;
+      arrToVar(length_collision2_name, (inbuffer + offset));
+      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;
+      uint32_t wrenches_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->wrenches_length);
+      if(wrenches_lengthT > wrenches_length)
+        this->wrenches = (geometry_msgs::Wrench*)realloc(this->wrenches, wrenches_lengthT * sizeof(geometry_msgs::Wrench));
+      wrenches_length = wrenches_lengthT;
+      for( uint32_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);
+      uint32_t contact_positions_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->contact_positions_length);
+      if(contact_positions_lengthT > contact_positions_length)
+        this->contact_positions = (geometry_msgs::Vector3*)realloc(this->contact_positions, contact_positions_lengthT * sizeof(geometry_msgs::Vector3));
+      contact_positions_length = contact_positions_lengthT;
+      for( uint32_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));
+      }
+      uint32_t contact_normals_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->contact_normals_length);
+      if(contact_normals_lengthT > contact_normals_length)
+        this->contact_normals = (geometry_msgs::Vector3*)realloc(this->contact_normals, contact_normals_lengthT * sizeof(geometry_msgs::Vector3));
+      contact_normals_length = contact_normals_lengthT;
+      for( uint32_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));
+      }
+      uint32_t depths_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->depths_length);
+      if(depths_lengthT > depths_length)
+        this->depths = (double*)realloc(this->depths, depths_lengthT * sizeof(double));
+      depths_length = depths_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ContactsState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t states_length;
+      typedef gazebo_msgs::ContactState _states_type;
+      _states_type st_states;
+      _states_type * 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 + 0) = (this->states_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->states_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->states_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->states_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->states_length);
+      for( uint32_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);
+      uint32_t states_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      states_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      states_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      states_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->states_length);
+      if(states_lengthT > states_length)
+        this->states = (gazebo_msgs::ContactState*)realloc(this->states, states_lengthT * sizeof(gazebo_msgs::ContactState));
+      states_length = states_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/DeleteModel.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,122 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+
+    DeleteModelRequest():
+      model_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      varToArr(outbuffer + offset, length_model_name);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetJointProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,291 @@
+#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:
+      typedef const char* _joint_name_type;
+      _joint_name_type joint_name;
+
+    GetJointPropertiesRequest():
+      joint_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      varToArr(outbuffer + offset, length_joint_name);
+      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;
+      arrToVar(length_joint_name, (inbuffer + offset));
+      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:
+      typedef uint8_t _type_type;
+      _type_type type;
+      uint32_t damping_length;
+      typedef double _damping_type;
+      _damping_type st_damping;
+      _damping_type * damping;
+      uint32_t position_length;
+      typedef double _position_type;
+      _position_type st_position;
+      _position_type * position;
+      uint32_t rate_length;
+      typedef double _rate_type;
+      _rate_type st_rate;
+      _rate_type * rate;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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 + 0) = (this->damping_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->damping_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->damping_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->damping_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->damping_length);
+      for( uint32_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 + 0) = (this->position_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->position_length);
+      for( uint32_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 + 0) = (this->rate_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->rate_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->rate_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->rate_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->rate_length);
+      for( uint32_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);
+      varToArr(outbuffer + offset, length_status_message);
+      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);
+      uint32_t damping_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->damping_length);
+      if(damping_lengthT > damping_length)
+        this->damping = (double*)realloc(this->damping, damping_lengthT * sizeof(double));
+      damping_length = damping_lengthT;
+      for( uint32_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));
+      }
+      uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->position_length);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      position_length = position_lengthT;
+      for( uint32_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));
+      }
+      uint32_t rate_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      rate_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      rate_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      rate_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->rate_length);
+      if(rate_lengthT > rate_length)
+        this->rate = (double*)realloc(this->rate, rate_lengthT * sizeof(double));
+      rate_length = rate_lengthT;
+      for( uint32_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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetLinkProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,370 @@
+#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:
+      typedef const char* _link_name_type;
+      _link_name_type link_name;
+
+    GetLinkPropertiesRequest():
+      link_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_link_name = strlen(this->link_name);
+      varToArr(outbuffer + offset, length_link_name);
+      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;
+      arrToVar(length_link_name, (inbuffer + offset));
+      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:
+      typedef geometry_msgs::Pose _com_type;
+      _com_type com;
+      typedef bool _gravity_mode_type;
+      _gravity_mode_type gravity_mode;
+      typedef double _mass_type;
+      _mass_type mass;
+      typedef double _ixx_type;
+      _ixx_type ixx;
+      typedef double _ixy_type;
+      _ixy_type ixy;
+      typedef double _ixz_type;
+      _ixz_type ixz;
+      typedef double _iyy_type;
+      _iyy_type iyy;
+      typedef double _iyz_type;
+      _iyz_type iyz;
+      typedef double _izz_type;
+      _izz_type izz;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetLinkState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,145 @@
+#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:
+      typedef const char* _link_name_type;
+      _link_name_type link_name;
+      typedef const char* _reference_frame_type;
+      _reference_frame_type 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);
+      varToArr(outbuffer + offset, length_link_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->link_name, length_link_name);
+      offset += length_link_name;
+      uint32_t length_reference_frame = strlen(this->reference_frame);
+      varToArr(outbuffer + offset, length_reference_frame);
+      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;
+      arrToVar(length_link_name, (inbuffer + offset));
+      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;
+      arrToVar(length_reference_frame, (inbuffer + offset));
+      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:
+      typedef gazebo_msgs::LinkState _link_state_type;
+      _link_state_type link_state;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetModelProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,322 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+
+    GetModelPropertiesRequest():
+      model_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_model_name = strlen(this->model_name);
+      varToArr(outbuffer + offset, length_model_name);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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:
+      typedef const char* _parent_model_name_type;
+      _parent_model_name_type parent_model_name;
+      typedef const char* _canonical_body_name_type;
+      _canonical_body_name_type canonical_body_name;
+      uint32_t body_names_length;
+      typedef char* _body_names_type;
+      _body_names_type st_body_names;
+      _body_names_type * body_names;
+      uint32_t geom_names_length;
+      typedef char* _geom_names_type;
+      _geom_names_type st_geom_names;
+      _geom_names_type * geom_names;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      uint32_t child_model_names_length;
+      typedef char* _child_model_names_type;
+      _child_model_names_type st_child_model_names;
+      _child_model_names_type * child_model_names;
+      typedef bool _is_static_type;
+      _is_static_type is_static;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_parent_model_name);
+      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);
+      varToArr(outbuffer + offset, length_canonical_body_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->canonical_body_name, length_canonical_body_name);
+      offset += length_canonical_body_name;
+      *(outbuffer + offset + 0) = (this->body_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->body_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->body_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->body_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->body_names_length);
+      for( uint32_t i = 0; i < body_names_length; i++){
+      uint32_t length_body_namesi = strlen(this->body_names[i]);
+      varToArr(outbuffer + offset, length_body_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->body_names[i], length_body_namesi);
+      offset += length_body_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->geom_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->geom_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->geom_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->geom_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->geom_names_length);
+      for( uint32_t i = 0; i < geom_names_length; i++){
+      uint32_t length_geom_namesi = strlen(this->geom_names[i]);
+      varToArr(outbuffer + offset, length_geom_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->geom_names[i], length_geom_namesi);
+      offset += length_geom_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->child_model_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->child_model_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->child_model_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->child_model_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->child_model_names_length);
+      for( uint32_t i = 0; i < child_model_names_length; i++){
+      uint32_t length_child_model_namesi = strlen(this->child_model_names[i]);
+      varToArr(outbuffer + offset, length_child_model_namesi);
+      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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_parent_model_name, (inbuffer + offset));
+      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;
+      arrToVar(length_canonical_body_name, (inbuffer + offset));
+      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;
+      uint32_t body_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->body_names_length);
+      if(body_names_lengthT > body_names_length)
+        this->body_names = (char**)realloc(this->body_names, body_names_lengthT * sizeof(char*));
+      body_names_length = body_names_lengthT;
+      for( uint32_t i = 0; i < body_names_length; i++){
+      uint32_t length_st_body_names;
+      arrToVar(length_st_body_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t geom_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->geom_names_length);
+      if(geom_names_lengthT > geom_names_length)
+        this->geom_names = (char**)realloc(this->geom_names, geom_names_lengthT * sizeof(char*));
+      geom_names_length = geom_names_lengthT;
+      for( uint32_t i = 0; i < geom_names_length; i++){
+      uint32_t length_st_geom_names;
+      arrToVar(length_st_geom_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t child_model_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->child_model_names_length);
+      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*));
+      child_model_names_length = child_model_names_lengthT;
+      for( uint32_t i = 0; i < child_model_names_length; i++){
+      uint32_t length_st_child_model_names;
+      arrToVar(length_st_child_model_names, (inbuffer + offset));
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetModelState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,157 @@
+#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"
+#include "std_msgs/Header.h"
+
+namespace gazebo_msgs
+{
+
+static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState";
+
+  class GetModelStateRequest : public ros::Msg
+  {
+    public:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+      typedef const char* _relative_entity_name_type;
+      _relative_entity_name_type 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);
+      varToArr(outbuffer + offset, length_model_name);
+      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);
+      varToArr(outbuffer + offset, length_relative_entity_name);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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;
+      arrToVar(length_relative_entity_name, (inbuffer + offset));
+      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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type twist;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type status_message;
+
+    GetModelStateResponse():
+      header(),
+      pose(),
+      twist(),
+      success(0),
+      status_message("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      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);
+      varToArr(outbuffer + offset, length_status_message);
+      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->header.deserialize(inbuffer + offset);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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 "ccd51739bb00f0141629e87b792e92b9"; };
+
+  };
+
+  class GetModelState {
+    public:
+    typedef GetModelStateRequest Request;
+    typedef GetModelStateResponse Response;
+  };
+
+}
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetPhysicsProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,199 @@
+#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:
+      typedef double _time_step_type;
+      _time_step_type time_step;
+      typedef bool _pause_type;
+      _pause_type pause;
+      typedef double _max_update_rate_type;
+      _max_update_rate_type max_update_rate;
+      typedef geometry_msgs::Vector3 _gravity_type;
+      _gravity_type gravity;
+      typedef gazebo_msgs::ODEPhysics _ode_config_type;
+      _ode_config_type ode_config;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/GetWorldProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,192 @@
+#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:
+      typedef double _sim_time_type;
+      _sim_time_type sim_time;
+      uint32_t model_names_length;
+      typedef char* _model_names_type;
+      _model_names_type st_model_names;
+      _model_names_type * model_names;
+      typedef bool _rendering_enabled_type;
+      _rendering_enabled_type rendering_enabled;
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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 + 0) = (this->model_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->model_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->model_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->model_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->model_names_length);
+      for( uint32_t i = 0; i < model_names_length; i++){
+      uint32_t length_model_namesi = strlen(this->model_names[i]);
+      varToArr(outbuffer + offset, length_model_namesi);
+      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);
+      varToArr(outbuffer + offset, length_status_message);
+      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);
+      uint32_t model_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->model_names_length);
+      if(model_names_lengthT > model_names_length)
+        this->model_names = (char**)realloc(this->model_names, model_names_lengthT * sizeof(char*));
+      model_names_length = model_names_lengthT;
+      for( uint32_t i = 0; i < model_names_length; i++){
+      uint32_t length_st_model_names;
+      arrToVar(length_st_model_names, (inbuffer + offset));
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/JointRequest.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _joint_name_type;
+      _joint_name_type joint_name;
+
+    JointRequestRequest():
+      joint_name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_joint_name = strlen(this->joint_name);
+      varToArr(outbuffer + offset, length_joint_name);
+      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;
+      arrToVar(length_joint_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/LinkState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,84 @@
+#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:
+      typedef const char* _link_name_type;
+      _link_name_type link_name;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type twist;
+      typedef const char* _reference_frame_type;
+      _reference_frame_type 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);
+      varToArr(outbuffer + offset, length_link_name);
+      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);
+      varToArr(outbuffer + offset, length_reference_frame);
+      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;
+      arrToVar(length_link_name, (inbuffer + offset));
+      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;
+      arrToVar(length_reference_frame, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/LinkStates.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,127 @@
+#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:
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t pose_length;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type st_pose;
+      _pose_type * pose;
+      uint32_t twist_length;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type st_twist;
+      _twist_type * 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 + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pose_length);
+      for( uint32_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->twist_length);
+      for( uint32_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;
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      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*));
+      }
+      uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->pose_length);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      pose_length = pose_lengthT;
+      for( uint32_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));
+      }
+      uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->twist_length);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      twist_length = twist_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ModelState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,84 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type twist;
+      typedef const char* _reference_frame_type;
+      _reference_frame_type 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);
+      varToArr(outbuffer + offset, length_model_name);
+      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);
+      varToArr(outbuffer + offset, length_reference_frame);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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;
+      arrToVar(length_reference_frame, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ModelStates.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,127 @@
+#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:
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t pose_length;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type st_pose;
+      _pose_type * pose;
+      uint32_t twist_length;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type st_twist;
+      _twist_type * 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 + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pose_length);
+      for( uint32_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->twist_length);
+      for( uint32_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;
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      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*));
+      }
+      uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->pose_length);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      pose_length = pose_lengthT;
+      for( uint32_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));
+      }
+      uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->twist_length);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      twist_length = twist_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ODEJointProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,558 @@
+#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:
+      uint32_t damping_length;
+      typedef double _damping_type;
+      _damping_type st_damping;
+      _damping_type * damping;
+      uint32_t hiStop_length;
+      typedef double _hiStop_type;
+      _hiStop_type st_hiStop;
+      _hiStop_type * hiStop;
+      uint32_t loStop_length;
+      typedef double _loStop_type;
+      _loStop_type st_loStop;
+      _loStop_type * loStop;
+      uint32_t erp_length;
+      typedef double _erp_type;
+      _erp_type st_erp;
+      _erp_type * erp;
+      uint32_t cfm_length;
+      typedef double _cfm_type;
+      _cfm_type st_cfm;
+      _cfm_type * cfm;
+      uint32_t stop_erp_length;
+      typedef double _stop_erp_type;
+      _stop_erp_type st_stop_erp;
+      _stop_erp_type * stop_erp;
+      uint32_t stop_cfm_length;
+      typedef double _stop_cfm_type;
+      _stop_cfm_type st_stop_cfm;
+      _stop_cfm_type * stop_cfm;
+      uint32_t fudge_factor_length;
+      typedef double _fudge_factor_type;
+      _fudge_factor_type st_fudge_factor;
+      _fudge_factor_type * fudge_factor;
+      uint32_t fmax_length;
+      typedef double _fmax_type;
+      _fmax_type st_fmax;
+      _fmax_type * fmax;
+      uint32_t vel_length;
+      typedef double _vel_type;
+      _vel_type st_vel;
+      _vel_type * 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 + 0) = (this->damping_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->damping_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->damping_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->damping_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->damping_length);
+      for( uint32_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 + 0) = (this->hiStop_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->hiStop_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->hiStop_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->hiStop_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->hiStop_length);
+      for( uint32_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 + 0) = (this->loStop_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->loStop_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->loStop_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->loStop_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->loStop_length);
+      for( uint32_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 + 0) = (this->erp_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->erp_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->erp_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->erp_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->erp_length);
+      for( uint32_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 + 0) = (this->cfm_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->cfm_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->cfm_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->cfm_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cfm_length);
+      for( uint32_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 + 0) = (this->stop_erp_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stop_erp_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stop_erp_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stop_erp_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stop_erp_length);
+      for( uint32_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 + 0) = (this->stop_cfm_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stop_cfm_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stop_cfm_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stop_cfm_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stop_cfm_length);
+      for( uint32_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 + 0) = (this->fudge_factor_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->fudge_factor_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->fudge_factor_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->fudge_factor_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->fudge_factor_length);
+      for( uint32_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 + 0) = (this->fmax_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->fmax_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->fmax_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->fmax_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->fmax_length);
+      for( uint32_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 + 0) = (this->vel_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->vel_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->vel_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->vel_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->vel_length);
+      for( uint32_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;
+      uint32_t damping_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      damping_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->damping_length);
+      if(damping_lengthT > damping_length)
+        this->damping = (double*)realloc(this->damping, damping_lengthT * sizeof(double));
+      damping_length = damping_lengthT;
+      for( uint32_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));
+      }
+      uint32_t hiStop_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      hiStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      hiStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      hiStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->hiStop_length);
+      if(hiStop_lengthT > hiStop_length)
+        this->hiStop = (double*)realloc(this->hiStop, hiStop_lengthT * sizeof(double));
+      hiStop_length = hiStop_lengthT;
+      for( uint32_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));
+      }
+      uint32_t loStop_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      loStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      loStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      loStop_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->loStop_length);
+      if(loStop_lengthT > loStop_length)
+        this->loStop = (double*)realloc(this->loStop, loStop_lengthT * sizeof(double));
+      loStop_length = loStop_lengthT;
+      for( uint32_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));
+      }
+      uint32_t erp_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->erp_length);
+      if(erp_lengthT > erp_length)
+        this->erp = (double*)realloc(this->erp, erp_lengthT * sizeof(double));
+      erp_length = erp_lengthT;
+      for( uint32_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));
+      }
+      uint32_t cfm_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->cfm_length);
+      if(cfm_lengthT > cfm_length)
+        this->cfm = (double*)realloc(this->cfm, cfm_lengthT * sizeof(double));
+      cfm_length = cfm_lengthT;
+      for( uint32_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));
+      }
+      uint32_t stop_erp_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      stop_erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      stop_erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      stop_erp_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->stop_erp_length);
+      if(stop_erp_lengthT > stop_erp_length)
+        this->stop_erp = (double*)realloc(this->stop_erp, stop_erp_lengthT * sizeof(double));
+      stop_erp_length = stop_erp_lengthT;
+      for( uint32_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));
+      }
+      uint32_t stop_cfm_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      stop_cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      stop_cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      stop_cfm_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->stop_cfm_length);
+      if(stop_cfm_lengthT > stop_cfm_length)
+        this->stop_cfm = (double*)realloc(this->stop_cfm, stop_cfm_lengthT * sizeof(double));
+      stop_cfm_length = stop_cfm_lengthT;
+      for( uint32_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));
+      }
+      uint32_t fudge_factor_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      fudge_factor_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      fudge_factor_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      fudge_factor_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->fudge_factor_length);
+      if(fudge_factor_lengthT > fudge_factor_length)
+        this->fudge_factor = (double*)realloc(this->fudge_factor, fudge_factor_lengthT * sizeof(double));
+      fudge_factor_length = fudge_factor_lengthT;
+      for( uint32_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));
+      }
+      uint32_t fmax_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      fmax_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      fmax_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      fmax_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->fmax_length);
+      if(fmax_lengthT > fmax_length)
+        this->fmax = (double*)realloc(this->fmax, fmax_lengthT * sizeof(double));
+      fmax_length = fmax_lengthT;
+      for( uint32_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));
+      }
+      uint32_t vel_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      vel_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      vel_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      vel_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->vel_length);
+      if(vel_lengthT > vel_length)
+        this->vel = (double*)realloc(this->vel, vel_lengthT * sizeof(double));
+      vel_length = vel_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/ODEPhysics.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,287 @@
+#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:
+      typedef bool _auto_disable_bodies_type;
+      _auto_disable_bodies_type auto_disable_bodies;
+      typedef uint32_t _sor_pgs_precon_iters_type;
+      _sor_pgs_precon_iters_type sor_pgs_precon_iters;
+      typedef uint32_t _sor_pgs_iters_type;
+      _sor_pgs_iters_type sor_pgs_iters;
+      typedef double _sor_pgs_w_type;
+      _sor_pgs_w_type sor_pgs_w;
+      typedef double _sor_pgs_rms_error_tol_type;
+      _sor_pgs_rms_error_tol_type sor_pgs_rms_error_tol;
+      typedef double _contact_surface_layer_type;
+      _contact_surface_layer_type contact_surface_layer;
+      typedef double _contact_max_correcting_vel_type;
+      _contact_max_correcting_vel_type contact_max_correcting_vel;
+      typedef double _cfm_type;
+      _cfm_type cfm;
+      typedef double _erp_type;
+      _erp_type erp;
+      typedef uint32_t _max_contacts_type;
+      _max_contacts_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetJointProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,128 @@
+#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:
+      typedef const char* _joint_name_type;
+      _joint_name_type joint_name;
+      typedef gazebo_msgs::ODEJointProperties _ode_joint_config_type;
+      _ode_joint_config_type 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);
+      varToArr(outbuffer + offset, length_joint_name);
+      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;
+      arrToVar(length_joint_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetJointTrajectory.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,170 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+      typedef trajectory_msgs::JointTrajectory _joint_trajectory_type;
+      _joint_trajectory_type joint_trajectory;
+      typedef geometry_msgs::Pose _model_pose_type;
+      _model_pose_type model_pose;
+      typedef bool _set_model_pose_type;
+      _set_model_pose_type set_model_pose;
+      typedef bool _disable_physics_updates_type;
+      _disable_physics_updates_type 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);
+      varToArr(outbuffer + offset, length_model_name);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetLinkProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,370 @@
+#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:
+      typedef const char* _link_name_type;
+      _link_name_type link_name;
+      typedef geometry_msgs::Pose _com_type;
+      _com_type com;
+      typedef bool _gravity_mode_type;
+      _gravity_mode_type gravity_mode;
+      typedef double _mass_type;
+      _mass_type mass;
+      typedef double _ixx_type;
+      _ixx_type ixx;
+      typedef double _ixy_type;
+      _ixy_type ixy;
+      typedef double _ixz_type;
+      _ixz_type ixz;
+      typedef double _iyy_type;
+      _iyy_type iyy;
+      typedef double _iyz_type;
+      _iyz_type iyz;
+      typedef double _izz_type;
+      _izz_type 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);
+      varToArr(outbuffer + offset, length_link_name);
+      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;
+      arrToVar(length_link_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetLinkState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,111 @@
+#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:
+      typedef gazebo_msgs::LinkState _link_state_type;
+      _link_state_type 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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetModelConfiguration.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,228 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+      typedef const char* _urdf_param_name_type;
+      _urdf_param_name_type urdf_param_name;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      uint32_t joint_positions_length;
+      typedef double _joint_positions_type;
+      _joint_positions_type st_joint_positions;
+      _joint_positions_type * 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);
+      varToArr(outbuffer + offset, length_model_name);
+      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);
+      varToArr(outbuffer + offset, length_urdf_param_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->urdf_param_name, length_urdf_param_name);
+      offset += length_urdf_param_name;
+      *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->joint_positions_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_positions_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_positions_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_positions_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_positions_length);
+      for( uint32_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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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;
+      arrToVar(length_urdf_param_name, (inbuffer + offset));
+      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;
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t joint_positions_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_positions_length);
+      if(joint_positions_lengthT > joint_positions_length)
+        this->joint_positions = (double*)realloc(this->joint_positions, joint_positions_lengthT * sizeof(double));
+      joint_positions_length = joint_positions_lengthT;
+      for( uint32_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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetModelState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,111 @@
+#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:
+      typedef gazebo_msgs::ModelState _model_state_type;
+      _model_state_type 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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SetPhysicsProperties.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,181 @@
+#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:
+      typedef double _time_step_type;
+      _time_step_type time_step;
+      typedef double _max_update_rate_type;
+      _max_update_rate_type max_update_rate;
+      typedef geometry_msgs::Vector3 _gravity_type;
+      _gravity_type gravity;
+      typedef gazebo_msgs::ODEPhysics _ode_config_type;
+      _ode_config_type 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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/SpawnModel.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,179 @@
+#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:
+      typedef const char* _model_name_type;
+      _model_name_type model_name;
+      typedef const char* _model_xml_type;
+      _model_xml_type model_xml;
+      typedef const char* _robot_namespace_type;
+      _robot_namespace_type robot_namespace;
+      typedef geometry_msgs::Pose _initial_pose_type;
+      _initial_pose_type initial_pose;
+      typedef const char* _reference_frame_type;
+      _reference_frame_type 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);
+      varToArr(outbuffer + offset, length_model_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_name, length_model_name);
+      offset += length_model_name;
+      uint32_t length_model_xml = strlen(this->model_xml);
+      varToArr(outbuffer + offset, length_model_xml);
+      offset += 4;
+      memcpy(outbuffer + offset, this->model_xml, length_model_xml);
+      offset += length_model_xml;
+      uint32_t length_robot_namespace = strlen(this->robot_namespace);
+      varToArr(outbuffer + offset, length_robot_namespace);
+      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);
+      varToArr(outbuffer + offset, length_reference_frame);
+      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;
+      arrToVar(length_model_name, (inbuffer + offset));
+      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;
+      arrToVar(length_model_xml, (inbuffer + offset));
+      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;
+      arrToVar(length_robot_namespace, (inbuffer + offset));
+      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;
+      arrToVar(length_reference_frame, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/gazebo_msgs/WorldState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,159 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t pose_length;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type st_pose;
+      _pose_type * pose;
+      uint32_t twist_length;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type st_twist;
+      _twist_type * twist;
+      uint32_t wrench_length;
+      typedef geometry_msgs::Wrench _wrench_type;
+      _wrench_type st_wrench;
+      _wrench_type * 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 + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->pose_length);
+      for( uint32_t i = 0; i < pose_length; i++){
+      offset += this->pose[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->twist_length);
+      for( uint32_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->wrench_length);
+      for( uint32_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);
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      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*));
+      }
+      uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->pose_length);
+      if(pose_lengthT > pose_length)
+        this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
+      pose_length = pose_lengthT;
+      for( uint32_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));
+      }
+      uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->twist_length);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      twist_length = twist_lengthT;
+      for( uint32_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));
+      }
+      uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->wrench_length);
+      if(wrench_lengthT > wrench_length)
+        this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
+      wrench_length = wrench_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Accel.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,49 @@
+#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:
+      typedef geometry_msgs::Vector3 _linear_type;
+      _linear_type linear;
+      typedef geometry_msgs::Vector3 _angular_type;
+      _angular_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Accel _accel_type;
+      _accel_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelWithCovariance.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef geometry_msgs::Accel _accel_type;
+      _accel_type accel;
+      double covariance[36];
+
+    AccelWithCovariance():
+      accel(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->accel.serialize(outbuffer + offset);
+      for( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/AccelWithCovarianceStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::AccelWithCovariance _accel_type;
+      _accel_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Inertia.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,268 @@
+#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:
+      typedef double _m_type;
+      _m_type m;
+      typedef geometry_msgs::Vector3 _com_type;
+      _com_type com;
+      typedef double _ixx_type;
+      _ixx_type ixx;
+      typedef double _ixy_type;
+      _ixy_type ixy;
+      typedef double _ixz_type;
+      _ixz_type ixz;
+      typedef double _iyy_type;
+      _iyy_type iyy;
+      typedef double _iyz_type;
+      _iyz_type iyz;
+      typedef double _izz_type;
+      _izz_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/InertiaStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Inertia _inertia_type;
+      _inertia_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _z_type;
+      _z_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point32.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,110 @@
+#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:
+      typedef float _x_type;
+      _x_type x;
+      typedef float _y_type;
+      _y_type y;
+      typedef float _z_type;
+      _z_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PointStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Point _point_type;
+      _point_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Polygon.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,64 @@
+#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:
+      uint32_t points_length;
+      typedef geometry_msgs::Point32 _points_type;
+      _points_type st_points;
+      _points_type * points;
+
+    Polygon():
+      points_length(0), points(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_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;
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
+      points_length = points_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PolygonStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Polygon _polygon_type;
+      _polygon_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef geometry_msgs::Point _position_type;
+      _position_type position;
+      typedef geometry_msgs::Quaternion _orientation_type;
+      _orientation_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose2D.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _theta_type;
+      _theta_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t poses_length;
+      typedef geometry_msgs::Pose _poses_type;
+      _poses_type st_poses;
+      _poses_type * 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 + 0) = (this->poses_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->poses_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->poses_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->poses_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->poses_length);
+      for( uint32_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);
+      uint32_t poses_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->poses_length);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose));
+      poses_length = poses_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovariance.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      double covariance[36];
+
+    PoseWithCovariance():
+      pose(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->pose.serialize(outbuffer + offset);
+      for( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovarianceStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::PoseWithCovariance _pose_type;
+      _pose_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Quaternion.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,166 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _z_type;
+      _z_type z;
+      typedef double _w_type;
+      _w_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/QuaternionStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Quaternion _quaternion_type;
+      _quaternion_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Transform.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef geometry_msgs::Vector3 _translation_type;
+      _translation_type translation;
+      typedef geometry_msgs::Quaternion _rotation_type;
+      _rotation_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TransformStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,67 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _child_frame_id_type;
+      _child_frame_id_type child_frame_id;
+      typedef geometry_msgs::Transform _transform_type;
+      _transform_type 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);
+      varToArr(outbuffer + offset, length_child_frame_id);
+      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;
+      arrToVar(length_child_frame_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Twist.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,49 @@
+#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:
+      typedef geometry_msgs::Vector3 _linear_type;
+      _linear_type linear;
+      typedef geometry_msgs::Vector3 _angular_type;
+      _angular_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovariance.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type twist;
+      double covariance[36];
+
+    TwistWithCovariance():
+      twist(),
+      covariance()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->twist.serialize(outbuffer + offset);
+      for( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovarianceStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::TwistWithCovariance _twist_type;
+      _twist_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _z_type;
+      _z_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3Stamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Vector3 _vector_type;
+      _vector_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Wrench.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,49 @@
+#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:
+      typedef geometry_msgs::Vector3 _force_type;
+      _force_type force;
+      typedef geometry_msgs::Vector3 _torque_type;
+      _torque_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/WrenchStamped.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Wrench _wrench_type;
+      _wrench_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/laser_assembler/AssembleScans.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,123 @@
+#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:
+      typedef ros::Time _begin_type;
+      _begin_type begin;
+      typedef ros::Time _end_type;
+      _end_type 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:
+      typedef sensor_msgs::PointCloud _cloud_type;
+      _cloud_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/laser_assembler/AssembleScans2.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,123 @@
+#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:
+      typedef ros::Time _begin_type;
+      _begin_type begin;
+      typedef ros::Time _end_type;
+      _end_type 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:
+      typedef sensor_msgs::PointCloud2 _cloud_type;
+      _cloud_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetMapROI.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,204 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _l_x_type;
+      _l_x_type l_x;
+      typedef double _l_y_type;
+      _l_y_type 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:
+      typedef nav_msgs::OccupancyGrid _sub_map_type;
+      _sub_map_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetPointMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,76 @@
+#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:
+      typedef sensor_msgs::PointCloud2 _map_type;
+      _map_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/GetPointMapROI.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,300 @@
+#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:
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _z_type;
+      _z_type z;
+      typedef double _r_type;
+      _r_type r;
+      typedef double _l_x_type;
+      _l_x_type l_x;
+      typedef double _l_y_type;
+      _l_y_type l_y;
+      typedef double _l_z_type;
+      _l_z_type 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:
+      typedef sensor_msgs::PointCloud2 _sub_map_type;
+      _sub_map_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/OccupancyGridUpdate.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,156 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef int32_t _x_type;
+      _x_type x;
+      typedef int32_t _y_type;
+      _y_type y;
+      typedef uint32_t _width_type;
+      _width_type width;
+      typedef uint32_t _height_type;
+      _height_type height;
+      uint32_t data_length;
+      typedef int8_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/PointCloud2Update.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,65 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef uint32_t _type_type;
+      _type_type type;
+      typedef sensor_msgs::PointCloud2 _points_type;
+      _points_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef nav_msgs::OccupancyGrid _map_type;
+      _map_type map;
+      typedef double _min_z_type;
+      _min_z_type min_z;
+      typedef double _max_z_type;
+      _max_z_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMapInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,247 @@
+#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:
+      typedef const char* _frame_id_type;
+      _frame_id_type frame_id;
+      typedef double _x_type;
+      _x_type x;
+      typedef double _y_type;
+      _y_type y;
+      typedef double _width_type;
+      _width_type width;
+      typedef double _height_type;
+      _height_type height;
+      typedef double _min_z_type;
+      _min_z_type min_z;
+      typedef double _max_z_type;
+      _max_z_type 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);
+      varToArr(outbuffer + offset, length_frame_id);
+      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;
+      arrToVar(length_frame_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/ProjectedMapsInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      uint32_t projected_maps_info_length;
+      typedef map_msgs::ProjectedMapInfo _projected_maps_info_type;
+      _projected_maps_info_type st_projected_maps_info;
+      _projected_maps_info_type * 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 + 0) = (this->projected_maps_info_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->projected_maps_info_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->projected_maps_info_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->projected_maps_info_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->projected_maps_info_length);
+      for( uint32_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;
+      uint32_t projected_maps_info_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->projected_maps_info_length);
+      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));
+      projected_maps_info_length = projected_maps_info_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/SaveMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,76 @@
+#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:
+      typedef std_msgs::String _filename_type;
+      _filename_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/map_msgs/SetMapProjections.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      uint32_t projected_maps_info_length;
+      typedef map_msgs::ProjectedMapInfo _projected_maps_info_type;
+      _projected_maps_info_type st_projected_maps_info;
+      _projected_maps_info_type * 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 + 0) = (this->projected_maps_info_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->projected_maps_info_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->projected_maps_info_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->projected_maps_info_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->projected_maps_info_length);
+      for( uint32_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;
+      uint32_t projected_maps_info_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->projected_maps_info_length);
+      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));
+      projected_maps_info_length = projected_maps_info_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,76 @@
+#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:
+      typedef nav_msgs::OccupancyGrid _map_type;
+      _map_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef nav_msgs::GetMapActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef nav_msgs::GetMapActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef nav_msgs::GetMapActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef nav_msgs::GetMapFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef nav_msgs::GetMapGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef nav_msgs::GetMapResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapGoal.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMapResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,44 @@
+#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:
+      typedef nav_msgs::OccupancyGrid _map_type;
+      _map_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetPlan.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,111 @@
+#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:
+      typedef geometry_msgs::PoseStamped _start_type;
+      _start_type start;
+      typedef geometry_msgs::PoseStamped _goal_type;
+      _goal_type goal;
+      typedef float _tolerance_type;
+      _tolerance_type 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:
+      typedef nav_msgs::Path _plan_type;
+      _plan_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GridCells.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,118 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef float _cell_width_type;
+      _cell_width_type cell_width;
+      typedef float _cell_height_type;
+      _cell_height_type cell_height;
+      uint32_t cells_length;
+      typedef geometry_msgs::Point _cells_type;
+      _cells_type st_cells;
+      _cells_type * 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 + 0) = (this->cells_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->cells_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->cells_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->cells_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cells_length);
+      for( uint32_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);
+      uint32_t cells_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      cells_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      cells_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      cells_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->cells_length);
+      if(cells_lengthT > cells_length)
+        this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point));
+      cells_length = cells_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/MapMetaData.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,118 @@
+#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:
+      typedef ros::Time _map_load_time_type;
+      _map_load_time_type map_load_time;
+      typedef float _resolution_type;
+      _resolution_type resolution;
+      typedef uint32_t _width_type;
+      _width_type width;
+      typedef uint32_t _height_type;
+      _height_type height;
+      typedef geometry_msgs::Pose _origin_type;
+      _origin_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/OccupancyGrid.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef nav_msgs::MapMetaData _info_type;
+      _info_type info;
+      uint32_t data_length;
+      typedef int8_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Odometry.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,73 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _child_frame_id_type;
+      _child_frame_id_type child_frame_id;
+      typedef geometry_msgs::PoseWithCovariance _pose_type;
+      _pose_type pose;
+      typedef geometry_msgs::TwistWithCovariance _twist_type;
+      _twist_type 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);
+      varToArr(outbuffer + offset, length_child_frame_id);
+      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;
+      arrToVar(length_child_frame_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Path.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t poses_length;
+      typedef geometry_msgs::PoseStamped _poses_type;
+      _poses_type st_poses;
+      _poses_type * 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 + 0) = (this->poses_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->poses_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->poses_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->poses_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->poses_length);
+      for( uint32_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);
+      uint32_t poses_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->poses_length);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped));
+      poses_length = poses_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/SetMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,100 @@
+#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:
+      typedef nav_msgs::OccupancyGrid _map_type;
+      _map_type map;
+      typedef geometry_msgs::PoseWithCovarianceStamped _initial_pose_type;
+      _initial_pose_type 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:
+      typedef bool _success_type;
+      _success_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletList.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,107 @@
+#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:
+      uint32_t nodelets_length;
+      typedef char* _nodelets_type;
+      _nodelets_type st_nodelets;
+      _nodelets_type * nodelets;
+
+    NodeletListResponse():
+      nodelets_length(0), nodelets(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->nodelets_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->nodelets_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->nodelets_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->nodelets_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->nodelets_length);
+      for( uint32_t i = 0; i < nodelets_length; i++){
+      uint32_t length_nodeletsi = strlen(this->nodelets[i]);
+      varToArr(outbuffer + offset, length_nodeletsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->nodelets[i], length_nodeletsi);
+      offset += length_nodeletsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t nodelets_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      nodelets_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      nodelets_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      nodelets_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->nodelets_length);
+      if(nodelets_lengthT > nodelets_length)
+        this->nodelets = (char**)realloc(this->nodelets, nodelets_lengthT * sizeof(char*));
+      nodelets_length = nodelets_lengthT;
+      for( uint32_t i = 0; i < nodelets_length; i++){
+      uint32_t length_st_nodelets;
+      arrToVar(length_st_nodelets, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletLoad.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,250 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _type_type;
+      _type_type type;
+      uint32_t remap_source_args_length;
+      typedef char* _remap_source_args_type;
+      _remap_source_args_type st_remap_source_args;
+      _remap_source_args_type * remap_source_args;
+      uint32_t remap_target_args_length;
+      typedef char* _remap_target_args_type;
+      _remap_target_args_type st_remap_target_args;
+      _remap_target_args_type * remap_target_args;
+      uint32_t my_argv_length;
+      typedef char* _my_argv_type;
+      _my_argv_type st_my_argv;
+      _my_argv_type * my_argv;
+      typedef const char* _bond_id_type;
+      _bond_id_type 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_type = strlen(this->type);
+      varToArr(outbuffer + offset, length_type);
+      offset += 4;
+      memcpy(outbuffer + offset, this->type, length_type);
+      offset += length_type;
+      *(outbuffer + offset + 0) = (this->remap_source_args_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->remap_source_args_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->remap_source_args_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->remap_source_args_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->remap_source_args_length);
+      for( uint32_t i = 0; i < remap_source_args_length; i++){
+      uint32_t length_remap_source_argsi = strlen(this->remap_source_args[i]);
+      varToArr(outbuffer + offset, length_remap_source_argsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->remap_source_args[i], length_remap_source_argsi);
+      offset += length_remap_source_argsi;
+      }
+      *(outbuffer + offset + 0) = (this->remap_target_args_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->remap_target_args_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->remap_target_args_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->remap_target_args_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->remap_target_args_length);
+      for( uint32_t i = 0; i < remap_target_args_length; i++){
+      uint32_t length_remap_target_argsi = strlen(this->remap_target_args[i]);
+      varToArr(outbuffer + offset, length_remap_target_argsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->remap_target_args[i], length_remap_target_argsi);
+      offset += length_remap_target_argsi;
+      }
+      *(outbuffer + offset + 0) = (this->my_argv_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->my_argv_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->my_argv_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->my_argv_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->my_argv_length);
+      for( uint32_t i = 0; i < my_argv_length; i++){
+      uint32_t length_my_argvi = strlen(this->my_argv[i]);
+      varToArr(outbuffer + offset, length_my_argvi);
+      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);
+      varToArr(outbuffer + offset, length_bond_id);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_type, (inbuffer + offset));
+      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;
+      uint32_t remap_source_args_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      remap_source_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      remap_source_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      remap_source_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->remap_source_args_length);
+      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*));
+      remap_source_args_length = remap_source_args_lengthT;
+      for( uint32_t i = 0; i < remap_source_args_length; i++){
+      uint32_t length_st_remap_source_args;
+      arrToVar(length_st_remap_source_args, (inbuffer + offset));
+      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*));
+      }
+      uint32_t remap_target_args_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      remap_target_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      remap_target_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      remap_target_args_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->remap_target_args_length);
+      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*));
+      remap_target_args_length = remap_target_args_lengthT;
+      for( uint32_t i = 0; i < remap_target_args_length; i++){
+      uint32_t length_st_remap_target_args;
+      arrToVar(length_st_remap_target_args, (inbuffer + offset));
+      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*));
+      }
+      uint32_t my_argv_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      my_argv_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      my_argv_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      my_argv_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->my_argv_length);
+      if(my_argv_lengthT > my_argv_length)
+        this->my_argv = (char**)realloc(this->my_argv, my_argv_lengthT * sizeof(char*));
+      my_argv_length = my_argv_lengthT;
+      for( uint32_t i = 0; i < my_argv_length; i++){
+      uint32_t length_st_my_argv;
+      arrToVar(length_st_my_argv, (inbuffer + offset));
+      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;
+      arrToVar(length_bond_id, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nodelet/NodeletUnload.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,105 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+
+    NodeletUnloadRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/ModelCoefficients.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t values_length;
+      typedef float _values_type;
+      _values_type st_values;
+      _values_type * 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 + 0) = (this->values_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->values_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->values_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->values_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values_length);
+      for( uint32_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);
+      uint32_t values_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->values_length);
+      if(values_lengthT > values_length)
+        this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
+      values_length = values_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/PointIndices.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t indices_length;
+      typedef int32_t _indices_type;
+      _indices_type st_indices;
+      _indices_type * 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 + 0) = (this->indices_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->indices_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->indices_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->indices_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->indices_length);
+      for( uint32_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);
+      uint32_t indices_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      indices_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      indices_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      indices_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->indices_length);
+      if(indices_lengthT > indices_length)
+        this->indices = (int32_t*)realloc(this->indices, indices_lengthT * sizeof(int32_t));
+      indices_length = indices_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/PolygonMesh.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,76 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef sensor_msgs::PointCloud2 _cloud_type;
+      _cloud_type cloud;
+      uint32_t polygons_length;
+      typedef pcl_msgs::Vertices _polygons_type;
+      _polygons_type st_polygons;
+      _polygons_type * 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 + 0) = (this->polygons_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->polygons_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->polygons_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->polygons_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->polygons_length);
+      for( uint32_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);
+      uint32_t polygons_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->polygons_length);
+      if(polygons_lengthT > polygons_length)
+        this->polygons = (pcl_msgs::Vertices*)realloc(this->polygons, polygons_lengthT * sizeof(pcl_msgs::Vertices));
+      polygons_length = polygons_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pcl_msgs/Vertices.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,71 @@
+#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:
+      uint32_t vertices_length;
+      typedef uint32_t _vertices_type;
+      _vertices_type st_vertices;
+      _vertices_type * vertices;
+
+    Vertices():
+      vertices_length(0), vertices(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->vertices_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->vertices_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->vertices_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->vertices_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->vertices_length);
+      for( uint32_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;
+      uint32_t vertices_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->vertices_length);
+      if(vertices_lengthT > vertices_length)
+        this->vertices = (uint32_t*)realloc(this->vertices, vertices_lengthT * sizeof(uint32_t));
+      vertices_length = vertices_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/polled_camera/GetPolledImage.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,202 @@
+#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:
+      typedef const char* _response_namespace_type;
+      _response_namespace_type response_namespace;
+      typedef ros::Duration _timeout_type;
+      _timeout_type timeout;
+      typedef uint32_t _binning_x_type;
+      _binning_x_type binning_x;
+      typedef uint32_t _binning_y_type;
+      _binning_y_type binning_y;
+      typedef sensor_msgs::RegionOfInterest _roi_type;
+      _roi_type 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);
+      varToArr(outbuffer + offset, length_response_namespace);
+      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;
+      arrToVar(length_response_namespace, (inbuffer + offset));
+      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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type status_message;
+      typedef ros::Time _stamp_type;
+      _stamp_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/duration.h	Sat Dec 31 00:48:34 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_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 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
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/msg.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,147 @@
+/*
+ * 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>
+#include <stddef.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;
+  }
+
+  // Copy data from variable into a byte array
+  template<typename A, typename V>
+  static void varToArr(A arr, const V var)
+  {
+    for(size_t i = 0; i < sizeof(V); i++)
+      arr[i] = (var >> (8 * i));
+  }
+
+  // Copy data from a byte array into variable
+  template<typename V, typename A>
+  static void arrToVar(V& var, const A arr)
+  {
+    var = 0;
+    for(size_t i = 0; i < sizeof(V); i++)
+      var |= (arr[i] << (8 * i));
+  }
+
+};
+
+}  // namespace ros
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/node_handle.h	Sat Dec 31 00:48:34 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 "ros/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 "ros/publisher.h"
+#include "ros/subscriber.h"
+#include "ros/service_server.h"
+#include "ros/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 SubscriberT>
+      bool subscribe(SubscriberT& s){
+        for(int i = 0; i < MAX_SUBSCRIBERS; i++){
+          if(subscribers[i] == 0){ // empty slot
+            subscribers[i] = static_cast<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] = static_cast<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] = static_cast<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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/publisher.h	Sat Dec 31 00:48:34 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 "ros/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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_client.h	Sat Dec 31 00:48:34 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 "ros/publisher.h"
+#include "ros/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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_server.h	Sat Dec 31 00:48:34 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 "ros/publisher.h"
+#include "ros/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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/subscriber.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,121 @@
+/*
+ * 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_;
+  };
+
+  /* Bound function subscriber. */
+  template<typename MsgT, typename ObjT=void>
+  class Subscriber: public Subscriber_
+  {
+    public:
+      typedef void(ObjT::*CallbackT)(const MsgT&);
+      MsgT msg;
+
+      Subscriber(const char * topic_name, CallbackT cb, ObjT* obj, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
+        cb_(cb),
+        obj_(obj),
+        endpoint_(endpoint)
+      {
+        topic_ = topic_name;
+      };
+
+      virtual void callback(unsigned char* data)
+      {
+        msg.deserialize(data);
+        (obj_->*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_;
+      ObjT* obj_;
+      int endpoint_;
+  };
+
+  /* Standalone function subscriber. */
+  template<typename MsgT>
+  class Subscriber<MsgT, void>: 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/time.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,72 @@
+/*
+ * 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 "ros/duration.h"
+#include <math.h>
+#include <stdint.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 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Empty.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/GetLoggers.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      uint32_t loggers_length;
+      typedef roscpp::Logger _loggers_type;
+      _loggers_type st_loggers;
+      _loggers_type * loggers;
+
+    GetLoggersResponse():
+      loggers_length(0), loggers(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->loggers_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->loggers_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->loggers_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->loggers_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->loggers_length);
+      for( uint32_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;
+      uint32_t loggers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      loggers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      loggers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      loggers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->loggers_length);
+      if(loggers_lengthT > loggers_length)
+        this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger));
+      loggers_length = loggers_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Logger.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,72 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _level_type;
+      _level_type level;
+
+    Logger():
+      name(""),
+      level("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_level = strlen(this->level);
+      varToArr(outbuffer + offset, length_level);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_level, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/SetLoggerLevel.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,104 @@
+#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:
+      typedef const char* _logger_type;
+      _logger_type logger;
+      typedef const char* _level_type;
+      _level_type level;
+
+    SetLoggerLevelRequest():
+      logger(""),
+      level("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_logger = strlen(this->logger);
+      varToArr(outbuffer + offset, length_logger);
+      offset += 4;
+      memcpy(outbuffer + offset, this->logger, length_logger);
+      offset += length_logger;
+      uint32_t length_level = strlen(this->level);
+      varToArr(outbuffer + offset, length_level);
+      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;
+      arrToVar(length_logger, (inbuffer + offset));
+      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;
+      arrToVar(length_level, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp_tutorials/TwoInts.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,166 @@
+#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:
+      typedef int64_t _a_type;
+      _a_type a;
+      typedef int64_t _b_type;
+      _b_type 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:
+      typedef int64_t _sum_type;
+      _sum_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Clock.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef ros::Time _clock_type;
+      _clock_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Log.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,185 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef int8_t _level_type;
+      _level_type level;
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _msg_type;
+      _msg_type msg;
+      typedef const char* _file_type;
+      _file_type file;
+      typedef const char* _function_type;
+      _function_type function;
+      typedef uint32_t _line_type;
+      _line_type line;
+      uint32_t topics_length;
+      typedef char* _topics_type;
+      _topics_type st_topics;
+      _topics_type * 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_msg = strlen(this->msg);
+      varToArr(outbuffer + offset, length_msg);
+      offset += 4;
+      memcpy(outbuffer + offset, this->msg, length_msg);
+      offset += length_msg;
+      uint32_t length_file = strlen(this->file);
+      varToArr(outbuffer + offset, length_file);
+      offset += 4;
+      memcpy(outbuffer + offset, this->file, length_file);
+      offset += length_file;
+      uint32_t length_function = strlen(this->function);
+      varToArr(outbuffer + offset, length_function);
+      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 + 0) = (this->topics_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->topics_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->topics_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->topics_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->topics_length);
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      varToArr(outbuffer + offset, length_topicsi);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_msg, (inbuffer + offset));
+      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;
+      arrToVar(length_file, (inbuffer + offset));
+      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;
+      arrToVar(length_function, (inbuffer + offset));
+      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);
+      uint32_t topics_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->topics_length);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      topics_length = topics_lengthT;
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      arrToVar(length_st_topics, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/TopicStatistics.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,347 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+      typedef const char* _node_pub_type;
+      _node_pub_type node_pub;
+      typedef const char* _node_sub_type;
+      _node_sub_type node_sub;
+      typedef ros::Time _window_start_type;
+      _window_start_type window_start;
+      typedef ros::Time _window_stop_type;
+      _window_stop_type window_stop;
+      typedef int32_t _delivered_msgs_type;
+      _delivered_msgs_type delivered_msgs;
+      typedef int32_t _dropped_msgs_type;
+      _dropped_msgs_type dropped_msgs;
+      typedef int32_t _traffic_type;
+      _traffic_type traffic;
+      typedef ros::Duration _period_mean_type;
+      _period_mean_type period_mean;
+      typedef ros::Duration _period_stddev_type;
+      _period_stddev_type period_stddev;
+      typedef ros::Duration _period_max_type;
+      _period_max_type period_max;
+      typedef ros::Duration _stamp_age_mean_type;
+      _stamp_age_mean_type stamp_age_mean;
+      typedef ros::Duration _stamp_age_stddev_type;
+      _stamp_age_stddev_type stamp_age_stddev;
+      typedef ros::Duration _stamp_age_max_type;
+      _stamp_age_max_type 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);
+      varToArr(outbuffer + offset, length_topic);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, length_topic);
+      offset += length_topic;
+      uint32_t length_node_pub = strlen(this->node_pub);
+      varToArr(outbuffer + offset, length_node_pub);
+      offset += 4;
+      memcpy(outbuffer + offset, this->node_pub, length_node_pub);
+      offset += length_node_pub;
+      uint32_t length_node_sub = strlen(this->node_sub);
+      varToArr(outbuffer + offset, length_node_sub);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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;
+      arrToVar(length_node_pub, (inbuffer + offset));
+      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;
+      arrToVar(length_node_sub, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/AddTwoInts.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,166 @@
+#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:
+      typedef int64_t _a_type;
+      _a_type a;
+      typedef int64_t _b_type;
+      _b_type 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:
+      typedef int64_t _sum_type;
+      _sum_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/BadTwoInts.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,150 @@
+#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:
+      typedef int64_t _a_type;
+      _a_type a;
+      typedef int32_t _b_type;
+      _b_type 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:
+      typedef int32_t _sum_type;
+      _sum_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/Floats.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      uint32_t data_length;
+      typedef float _data_type;
+      _data_type st_data;
+      _data_type * data;
+
+    Floats():
+      data_length(0), data(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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;
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rospy_tutorials/HeaderString.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,61 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _data_type;
+      _data_type 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);
+      varToArr(outbuffer + offset, length_data);
+      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;
+      arrToVar(length_data, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_arduino/Adc.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,92 @@
+#ifndef _ROS_rosserial_arduino_Adc_h
+#define _ROS_rosserial_arduino_Adc_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_arduino
+{
+
+  class Adc : public ros::Msg
+  {
+    public:
+      typedef uint16_t _adc0_type;
+      _adc0_type adc0;
+      typedef uint16_t _adc1_type;
+      _adc1_type adc1;
+      typedef uint16_t _adc2_type;
+      _adc2_type adc2;
+      typedef uint16_t _adc3_type;
+      _adc3_type adc3;
+      typedef uint16_t _adc4_type;
+      _adc4_type adc4;
+      typedef uint16_t _adc5_type;
+      _adc5_type 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_arduino/Adc"; };
+    const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_arduino/Test.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,104 @@
+#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_arduino
+{
+
+static const char TEST[] = "rosserial_arduino/Test";
+
+  class TestRequest : public ros::Msg
+  {
+    public:
+      typedef const char* _input_type;
+      _input_type input;
+
+    TestRequest():
+      input("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_input = strlen(this->input);
+      varToArr(outbuffer + offset, length_input);
+      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;
+      arrToVar(length_input, (inbuffer + offset));
+      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:
+      typedef const char* _output_type;
+      _output_type output;
+
+    TestResponse():
+      output("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_output = strlen(this->output);
+      varToArr(outbuffer + offset, length_output);
+      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;
+      arrToVar(length_output, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_mbed/Adc.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,92 @@
+#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:
+      typedef uint16_t _adc0_type;
+      _adc0_type adc0;
+      typedef uint16_t _adc1_type;
+      _adc1_type adc1;
+      typedef uint16_t _adc2_type;
+      _adc2_type adc2;
+      typedef uint16_t _adc3_type;
+      _adc3_type adc3;
+      typedef uint16_t _adc4_type;
+      _adc4_type adc4;
+      typedef uint16_t _adc5_type;
+      _adc5_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_mbed/Test.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,104 @@
+#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:
+      typedef const char* _input_type;
+      _input_type input;
+
+    TestRequest():
+      input("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_input = strlen(this->input);
+      varToArr(outbuffer + offset, length_input);
+      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;
+      arrToVar(length_input, (inbuffer + offset));
+      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:
+      typedef const char* _output_type;
+      _output_type output;
+
+    TestResponse():
+      output("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_output = strlen(this->output);
+      varToArr(outbuffer + offset, length_output);
+      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;
+      arrToVar(length_output, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/Log.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,67 @@
+#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:
+      typedef uint8_t _level_type;
+      _level_type level;
+      typedef const char* _msg_type;
+      _msg_type 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);
+      varToArr(outbuffer + offset, length_msg);
+      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;
+      arrToVar(length_msg, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestMessageInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,121 @@
+#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:
+      typedef const char* _type_type;
+      _type_type type;
+
+    RequestMessageInfoRequest():
+      type("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_type = strlen(this->type);
+      varToArr(outbuffer + offset, length_type);
+      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;
+      arrToVar(length_type, (inbuffer + offset));
+      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:
+      typedef const char* _md5_type;
+      _md5_type md5;
+      typedef const char* _definition_type;
+      _definition_type definition;
+
+    RequestMessageInfoResponse():
+      md5(""),
+      definition("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_md5 = strlen(this->md5);
+      varToArr(outbuffer + offset, length_md5);
+      offset += 4;
+      memcpy(outbuffer + offset, this->md5, length_md5);
+      offset += length_md5;
+      uint32_t length_definition = strlen(this->definition);
+      varToArr(outbuffer + offset, length_definition);
+      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;
+      arrToVar(length_md5, (inbuffer + offset));
+      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;
+      arrToVar(length_definition, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestParam.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,212 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+
+    RequestParamRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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:
+      uint32_t ints_length;
+      typedef int32_t _ints_type;
+      _ints_type st_ints;
+      _ints_type * ints;
+      uint32_t floats_length;
+      typedef float _floats_type;
+      _floats_type st_floats;
+      _floats_type * floats;
+      uint32_t strings_length;
+      typedef char* _strings_type;
+      _strings_type st_strings;
+      _strings_type * 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 + 0) = (this->ints_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->ints_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->ints_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->ints_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ints_length);
+      for( uint32_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 + 0) = (this->floats_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->floats_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->floats_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->floats_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->floats_length);
+      for( uint32_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 + 0) = (this->strings_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->strings_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->strings_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->strings_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->strings_length);
+      for( uint32_t i = 0; i < strings_length; i++){
+      uint32_t length_stringsi = strlen(this->strings[i]);
+      varToArr(outbuffer + offset, length_stringsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->strings[i], length_stringsi);
+      offset += length_stringsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t ints_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      ints_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->ints_length);
+      if(ints_lengthT > ints_length)
+        this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t));
+      ints_length = ints_lengthT;
+      for( uint32_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));
+      }
+      uint32_t floats_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      floats_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->floats_length);
+      if(floats_lengthT > floats_length)
+        this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
+      floats_length = floats_lengthT;
+      for( uint32_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));
+      }
+      uint32_t strings_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      strings_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->strings_length);
+      if(strings_lengthT > strings_length)
+        this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
+      strings_length = strings_lengthT;
+      for( uint32_t i = 0; i < strings_length; i++){
+      uint32_t length_st_strings;
+      arrToVar(length_st_strings, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestServiceInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,138 @@
+#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:
+      typedef const char* _service_type;
+      _service_type service;
+
+    RequestServiceInfoRequest():
+      service("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_service = strlen(this->service);
+      varToArr(outbuffer + offset, length_service);
+      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;
+      arrToVar(length_service, (inbuffer + offset));
+      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:
+      typedef const char* _service_md5_type;
+      _service_md5_type service_md5;
+      typedef const char* _request_md5_type;
+      _request_md5_type request_md5;
+      typedef const char* _response_md5_type;
+      _response_md5_type 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);
+      varToArr(outbuffer + offset, length_service_md5);
+      offset += 4;
+      memcpy(outbuffer + offset, this->service_md5, length_service_md5);
+      offset += length_service_md5;
+      uint32_t length_request_md5 = strlen(this->request_md5);
+      varToArr(outbuffer + offset, length_request_md5);
+      offset += 4;
+      memcpy(outbuffer + offset, this->request_md5, length_request_md5);
+      offset += length_request_md5;
+      uint32_t length_response_md5 = strlen(this->response_md5);
+      varToArr(outbuffer + offset, length_response_md5);
+      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;
+      arrToVar(length_service_md5, (inbuffer + offset));
+      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;
+      arrToVar(length_request_md5, (inbuffer + offset));
+      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;
+      arrToVar(length_response_md5, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/TopicInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,130 @@
+#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:
+      typedef uint16_t _topic_id_type;
+      _topic_id_type topic_id;
+      typedef const char* _topic_name_type;
+      _topic_name_type topic_name;
+      typedef const char* _message_type_type;
+      _message_type_type message_type;
+      typedef const char* _md5sum_type;
+      _md5sum_type md5sum;
+      typedef int32_t _buffer_size_type;
+      _buffer_size_type 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);
+      varToArr(outbuffer + offset, length_topic_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic_name, length_topic_name);
+      offset += length_topic_name;
+      uint32_t length_message_type = strlen(this->message_type);
+      varToArr(outbuffer + offset, length_message_type);
+      offset += 4;
+      memcpy(outbuffer + offset, this->message_type, length_message_type);
+      offset += length_message_type;
+      uint32_t length_md5sum = strlen(this->md5sum);
+      varToArr(outbuffer + offset, length_md5sum);
+      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;
+      arrToVar(length_topic_name, (inbuffer + offset));
+      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;
+      arrToVar(length_message_type, (inbuffer + offset));
+      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;
+      arrToVar(length_md5sum, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/BatteryState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,326 @@
+#ifndef _ROS_sensor_msgs_BatteryState_h
+#define _ROS_sensor_msgs_BatteryState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class BatteryState : public ros::Msg
+  {
+    public:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef float _voltage_type;
+      _voltage_type voltage;
+      typedef float _current_type;
+      _current_type current;
+      typedef float _charge_type;
+      _charge_type charge;
+      typedef float _capacity_type;
+      _capacity_type capacity;
+      typedef float _design_capacity_type;
+      _design_capacity_type design_capacity;
+      typedef float _percentage_type;
+      _percentage_type percentage;
+      typedef uint8_t _power_supply_status_type;
+      _power_supply_status_type power_supply_status;
+      typedef uint8_t _power_supply_health_type;
+      _power_supply_health_type power_supply_health;
+      typedef uint8_t _power_supply_technology_type;
+      _power_supply_technology_type power_supply_technology;
+      typedef bool _present_type;
+      _present_type present;
+      uint32_t cell_voltage_length;
+      typedef float _cell_voltage_type;
+      _cell_voltage_type st_cell_voltage;
+      _cell_voltage_type * cell_voltage;
+      typedef const char* _location_type;
+      _location_type location;
+      typedef const char* _serial_number_type;
+      _serial_number_type serial_number;
+      enum { POWER_SUPPLY_STATUS_UNKNOWN =  0 };
+      enum { POWER_SUPPLY_STATUS_CHARGING =  1 };
+      enum { POWER_SUPPLY_STATUS_DISCHARGING =  2 };
+      enum { POWER_SUPPLY_STATUS_NOT_CHARGING =  3 };
+      enum { POWER_SUPPLY_STATUS_FULL =  4 };
+      enum { POWER_SUPPLY_HEALTH_UNKNOWN =  0 };
+      enum { POWER_SUPPLY_HEALTH_GOOD =  1 };
+      enum { POWER_SUPPLY_HEALTH_OVERHEAT =  2 };
+      enum { POWER_SUPPLY_HEALTH_DEAD =  3 };
+      enum { POWER_SUPPLY_HEALTH_OVERVOLTAGE =  4 };
+      enum { POWER_SUPPLY_HEALTH_UNSPEC_FAILURE =  5 };
+      enum { POWER_SUPPLY_HEALTH_COLD =  6 };
+      enum { POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE =  7 };
+      enum { POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE =  8 };
+      enum { POWER_SUPPLY_TECHNOLOGY_UNKNOWN =  0 };
+      enum { POWER_SUPPLY_TECHNOLOGY_NIMH =  1 };
+      enum { POWER_SUPPLY_TECHNOLOGY_LION =  2 };
+      enum { POWER_SUPPLY_TECHNOLOGY_LIPO =  3 };
+      enum { POWER_SUPPLY_TECHNOLOGY_LIFE =  4 };
+      enum { POWER_SUPPLY_TECHNOLOGY_NICD =  5 };
+      enum { POWER_SUPPLY_TECHNOLOGY_LIMN =  6 };
+
+    BatteryState():
+      header(),
+      voltage(0),
+      current(0),
+      charge(0),
+      capacity(0),
+      design_capacity(0),
+      percentage(0),
+      power_supply_status(0),
+      power_supply_health(0),
+      power_supply_technology(0),
+      present(0),
+      cell_voltage_length(0), cell_voltage(NULL),
+      location(""),
+      serial_number("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_voltage;
+      u_voltage.real = this->voltage;
+      *(outbuffer + offset + 0) = (u_voltage.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_voltage.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_voltage.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_voltage.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->voltage);
+      union {
+        float real;
+        uint32_t base;
+      } u_current;
+      u_current.real = this->current;
+      *(outbuffer + offset + 0) = (u_current.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_current.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_current.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_current.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->current);
+      union {
+        float real;
+        uint32_t base;
+      } u_charge;
+      u_charge.real = this->charge;
+      *(outbuffer + offset + 0) = (u_charge.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_charge.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_charge.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_charge.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->charge);
+      union {
+        float real;
+        uint32_t base;
+      } u_capacity;
+      u_capacity.real = this->capacity;
+      *(outbuffer + offset + 0) = (u_capacity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_capacity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_capacity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_capacity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->capacity);
+      union {
+        float real;
+        uint32_t base;
+      } u_design_capacity;
+      u_design_capacity.real = this->design_capacity;
+      *(outbuffer + offset + 0) = (u_design_capacity.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_design_capacity.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_design_capacity.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_design_capacity.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->design_capacity);
+      union {
+        float real;
+        uint32_t base;
+      } u_percentage;
+      u_percentage.real = this->percentage;
+      *(outbuffer + offset + 0) = (u_percentage.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_percentage.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_percentage.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_percentage.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->percentage);
+      *(outbuffer + offset + 0) = (this->power_supply_status >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->power_supply_status);
+      *(outbuffer + offset + 0) = (this->power_supply_health >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->power_supply_health);
+      *(outbuffer + offset + 0) = (this->power_supply_technology >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->power_supply_technology);
+      union {
+        bool real;
+        uint8_t base;
+      } u_present;
+      u_present.real = this->present;
+      *(outbuffer + offset + 0) = (u_present.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->present);
+      *(outbuffer + offset + 0) = (this->cell_voltage_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->cell_voltage_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->cell_voltage_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->cell_voltage_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_voltage_length);
+      for( uint32_t i = 0; i < cell_voltage_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_cell_voltagei;
+      u_cell_voltagei.real = this->cell_voltage[i];
+      *(outbuffer + offset + 0) = (u_cell_voltagei.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cell_voltagei.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cell_voltagei.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cell_voltagei.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_voltage[i]);
+      }
+      uint32_t length_location = strlen(this->location);
+      varToArr(outbuffer + offset, length_location);
+      offset += 4;
+      memcpy(outbuffer + offset, this->location, length_location);
+      offset += length_location;
+      uint32_t length_serial_number = strlen(this->serial_number);
+      varToArr(outbuffer + offset, length_serial_number);
+      offset += 4;
+      memcpy(outbuffer + offset, this->serial_number, length_serial_number);
+      offset += length_serial_number;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        uint32_t base;
+      } u_voltage;
+      u_voltage.base = 0;
+      u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->voltage = u_voltage.real;
+      offset += sizeof(this->voltage);
+      union {
+        float real;
+        uint32_t base;
+      } u_current;
+      u_current.base = 0;
+      u_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->current = u_current.real;
+      offset += sizeof(this->current);
+      union {
+        float real;
+        uint32_t base;
+      } u_charge;
+      u_charge.base = 0;
+      u_charge.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_charge.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_charge.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_charge.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->charge = u_charge.real;
+      offset += sizeof(this->charge);
+      union {
+        float real;
+        uint32_t base;
+      } u_capacity;
+      u_capacity.base = 0;
+      u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->capacity = u_capacity.real;
+      offset += sizeof(this->capacity);
+      union {
+        float real;
+        uint32_t base;
+      } u_design_capacity;
+      u_design_capacity.base = 0;
+      u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->design_capacity = u_design_capacity.real;
+      offset += sizeof(this->design_capacity);
+      union {
+        float real;
+        uint32_t base;
+      } u_percentage;
+      u_percentage.base = 0;
+      u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->percentage = u_percentage.real;
+      offset += sizeof(this->percentage);
+      this->power_supply_status =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->power_supply_status);
+      this->power_supply_health =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->power_supply_health);
+      this->power_supply_technology =  ((uint8_t) (*(inbuffer + offset)));
+      offset += sizeof(this->power_supply_technology);
+      union {
+        bool real;
+        uint8_t base;
+      } u_present;
+      u_present.base = 0;
+      u_present.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->present = u_present.real;
+      offset += sizeof(this->present);
+      uint32_t cell_voltage_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->cell_voltage_length);
+      if(cell_voltage_lengthT > cell_voltage_length)
+        this->cell_voltage = (float*)realloc(this->cell_voltage, cell_voltage_lengthT * sizeof(float));
+      cell_voltage_length = cell_voltage_lengthT;
+      for( uint32_t i = 0; i < cell_voltage_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_cell_voltage;
+      u_st_cell_voltage.base = 0;
+      u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_cell_voltage = u_st_cell_voltage.real;
+      offset += sizeof(this->st_cell_voltage);
+        memcpy( &(this->cell_voltage[i]), &(this->st_cell_voltage), sizeof(float));
+      }
+      uint32_t length_location;
+      arrToVar(length_location, (inbuffer + offset));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_location; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_location-1]=0;
+      this->location = (char *)(inbuffer + offset-1);
+      offset += length_location;
+      uint32_t length_serial_number;
+      arrToVar(length_serial_number, (inbuffer + offset));
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_serial_number; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_serial_number-1]=0;
+      this->serial_number = (char *)(inbuffer + offset-1);
+      offset += length_serial_number;
+     return offset;
+    }
+
+    const char * getType(){ return "sensor_msgs/BatteryState"; };
+    const char * getMD5(){ return "476f837fa6771f6e16e3bf4ef96f8770"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CameraInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,276 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef uint32_t _height_type;
+      _height_type height;
+      typedef uint32_t _width_type;
+      _width_type width;
+      typedef const char* _distortion_model_type;
+      _distortion_model_type distortion_model;
+      uint32_t D_length;
+      typedef double _D_type;
+      _D_type st_D;
+      _D_type * D;
+      double K[9];
+      double R[9];
+      double P[12];
+      typedef uint32_t _binning_x_type;
+      _binning_x_type binning_x;
+      typedef uint32_t _binning_y_type;
+      _binning_y_type binning_y;
+      typedef sensor_msgs::RegionOfInterest _roi_type;
+      _roi_type 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);
+      varToArr(outbuffer + offset, length_distortion_model);
+      offset += 4;
+      memcpy(outbuffer + offset, this->distortion_model, length_distortion_model);
+      offset += length_distortion_model;
+      *(outbuffer + offset + 0) = (this->D_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->D_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->D_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->D_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->D_length);
+      for( uint32_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( uint32_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( uint32_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( uint32_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;
+      arrToVar(length_distortion_model, (inbuffer + offset));
+      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;
+      uint32_t D_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      D_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      D_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      D_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->D_length);
+      if(D_lengthT > D_length)
+        this->D = (double*)realloc(this->D, D_lengthT * sizeof(double));
+      D_length = D_lengthT;
+      for( uint32_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( uint32_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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/ChannelFloat32.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,99 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      uint32_t values_length;
+      typedef float _values_type;
+      _values_type st_values;
+      _values_type * 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      *(outbuffer + offset + 0) = (this->values_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->values_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->values_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->values_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values_length);
+      for( uint32_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;
+      arrToVar(length_name, (inbuffer + offset));
+      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 values_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      values_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->values_length);
+      if(values_lengthT > values_length)
+        this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
+      values_length = values_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CompressedImage.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _format_type;
+      _format_type format;
+      uint32_t data_length;
+      typedef uint8_t _data_type;
+      _data_type st_data;
+      _data_type * 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);
+      varToArr(outbuffer + offset, length_format);
+      offset += 4;
+      memcpy(outbuffer + offset, this->format, length_format);
+      offset += length_format;
+      *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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;
+      arrToVar(length_format, (inbuffer + offset));
+      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;
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/FluidPressure.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _fluid_pressure_type;
+      _fluid_pressure_type fluid_pressure;
+      typedef double _variance_type;
+      _variance_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Illuminance.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _illuminance_type;
+      _illuminance_type illuminance;
+      typedef double _variance_type;
+      _variance_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Image.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef uint32_t _height_type;
+      _height_type height;
+      typedef uint32_t _width_type;
+      _width_type width;
+      typedef const char* _encoding_type;
+      _encoding_type encoding;
+      typedef uint8_t _is_bigendian_type;
+      _is_bigendian_type is_bigendian;
+      typedef uint32_t _step_type;
+      _step_type step;
+      uint32_t data_length;
+      typedef uint8_t _data_type;
+      _data_type st_data;
+      _data_type * 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);
+      varToArr(outbuffer + offset, length_encoding);
+      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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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;
+      arrToVar(length_encoding, (inbuffer + offset));
+      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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Imu.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,166 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Quaternion _orientation_type;
+      _orientation_type orientation;
+      double orientation_covariance[9];
+      typedef geometry_msgs::Vector3 _angular_velocity_type;
+      _angular_velocity_type angular_velocity;
+      double angular_velocity_covariance[9];
+      typedef geometry_msgs::Vector3 _linear_acceleration_type;
+      _linear_acceleration_type 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( uint32_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( uint32_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( uint32_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( uint32_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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JointState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,237 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t name_length;
+      typedef char* _name_type;
+      _name_type st_name;
+      _name_type * name;
+      uint32_t position_length;
+      typedef double _position_type;
+      _position_type st_position;
+      _position_type * position;
+      uint32_t velocity_length;
+      typedef double _velocity_type;
+      _velocity_type st_velocity;
+      _velocity_type * velocity;
+      uint32_t effort_length;
+      typedef double _effort_type;
+      _effort_type st_effort;
+      _effort_type * 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 + 0) = (this->name_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->name_length);
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_namei = strlen(this->name[i]);
+      varToArr(outbuffer + offset, length_namei);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], length_namei);
+      offset += length_namei;
+      }
+      *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->position_length);
+      for( uint32_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 + 0) = (this->velocity_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->velocity_length);
+      for( uint32_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 + 0) = (this->effort_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->effort_length);
+      for( uint32_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);
+      uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->name_length);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      name_length = name_lengthT;
+      for( uint32_t i = 0; i < name_length; i++){
+      uint32_t length_st_name;
+      arrToVar(length_st_name, (inbuffer + offset));
+      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*));
+      }
+      uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->position_length);
+      if(position_lengthT > position_length)
+        this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
+      position_length = position_lengthT;
+      for( uint32_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));
+      }
+      uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->velocity_length);
+      if(velocity_lengthT > velocity_length)
+        this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
+      velocity_length = velocity_lengthT;
+      for( uint32_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));
+      }
+      uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->effort_length);
+      if(effort_lengthT > effort_length)
+        this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
+      effort_length = effort_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Joy.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,132 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t axes_length;
+      typedef float _axes_type;
+      _axes_type st_axes;
+      _axes_type * axes;
+      uint32_t buttons_length;
+      typedef int32_t _buttons_type;
+      _buttons_type st_buttons;
+      _buttons_type * 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 + 0) = (this->axes_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->axes_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->axes_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->axes_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->axes_length);
+      for( uint32_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 + 0) = (this->buttons_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->buttons_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->buttons_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->buttons_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->buttons_length);
+      for( uint32_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);
+      uint32_t axes_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      axes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->axes_length);
+      if(axes_lengthT > axes_length)
+        this->axes = (float*)realloc(this->axes, axes_lengthT * sizeof(float));
+      axes_length = axes_lengthT;
+      for( uint32_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));
+      }
+      uint32_t buttons_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      buttons_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->buttons_length);
+      if(buttons_lengthT > buttons_length)
+        this->buttons = (int32_t*)realloc(this->buttons, buttons_lengthT * sizeof(int32_t));
+      buttons_length = buttons_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JoyFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,79 @@
+#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:
+      typedef uint8_t _type_type;
+      _type_type type;
+      typedef uint8_t _id_type;
+      _id_type id;
+      typedef float _intensity_type;
+      _intensity_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JoyFeedbackArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,64 @@
+#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:
+      uint32_t array_length;
+      typedef sensor_msgs::JoyFeedback _array_type;
+      _array_type st_array;
+      _array_type * array;
+
+    JoyFeedbackArray():
+      array_length(0), array(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->array_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->array_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->array_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->array_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->array_length);
+      for( uint32_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;
+      uint32_t array_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      array_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      array_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      array_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->array_length);
+      if(array_lengthT > array_length)
+        this->array = (sensor_msgs::JoyFeedback*)realloc(this->array, array_lengthT * sizeof(sensor_msgs::JoyFeedback));
+      array_length = array_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/LaserEcho.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      uint32_t echoes_length;
+      typedef float _echoes_type;
+      _echoes_type st_echoes;
+      _echoes_type * echoes;
+
+    LaserEcho():
+      echoes_length(0), echoes(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->echoes_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->echoes_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->echoes_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->echoes_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->echoes_length);
+      for( uint32_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;
+      uint32_t echoes_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      echoes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->echoes_length);
+      if(echoes_lengthT > echoes_length)
+        this->echoes = (float*)realloc(this->echoes, echoes_lengthT * sizeof(float));
+      echoes_length = echoes_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/LaserScan.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,300 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef float _angle_min_type;
+      _angle_min_type angle_min;
+      typedef float _angle_max_type;
+      _angle_max_type angle_max;
+      typedef float _angle_increment_type;
+      _angle_increment_type angle_increment;
+      typedef float _time_increment_type;
+      _time_increment_type time_increment;
+      typedef float _scan_time_type;
+      _scan_time_type scan_time;
+      typedef float _range_min_type;
+      _range_min_type range_min;
+      typedef float _range_max_type;
+      _range_max_type range_max;
+      uint32_t ranges_length;
+      typedef float _ranges_type;
+      _ranges_type st_ranges;
+      _ranges_type * ranges;
+      uint32_t intensities_length;
+      typedef float _intensities_type;
+      _intensities_type st_intensities;
+      _intensities_type * 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 + 0) = (this->ranges_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->ranges_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->ranges_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->ranges_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ranges_length);
+      for( uint32_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 + 0) = (this->intensities_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->intensities_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->intensities_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->intensities_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->intensities_length);
+      for( uint32_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);
+      uint32_t ranges_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->ranges_length);
+      if(ranges_lengthT > ranges_length)
+        this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float));
+      ranges_length = ranges_lengthT;
+      for( uint32_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));
+      }
+      uint32_t intensities_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->intensities_length);
+      if(intensities_lengthT > intensities_length)
+        this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float));
+      intensities_length = intensities_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MagneticField.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,85 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Vector3 _magnetic_field_type;
+      _magnetic_field_type 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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MultiDOFJointState.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,159 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      uint32_t transforms_length;
+      typedef geometry_msgs::Transform _transforms_type;
+      _transforms_type st_transforms;
+      _transforms_type * transforms;
+      uint32_t twist_length;
+      typedef geometry_msgs::Twist _twist_type;
+      _twist_type st_twist;
+      _twist_type * twist;
+      uint32_t wrench_length;
+      typedef geometry_msgs::Wrench _wrench_type;
+      _wrench_type st_wrench;
+      _wrench_type * 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 + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->transforms_length);
+      for( uint32_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->twist_length);
+      for( uint32_t i = 0; i < twist_length; i++){
+      offset += this->twist[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->wrench_length);
+      for( uint32_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);
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->transforms_length);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
+      transforms_length = transforms_lengthT;
+      for( uint32_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));
+      }
+      uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->twist_length);
+      if(twist_lengthT > twist_length)
+        this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
+      twist_length = twist_lengthT;
+      for( uint32_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));
+      }
+      uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->wrench_length);
+      if(wrench_lengthT > wrench_length)
+        this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
+      wrench_length = wrench_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/MultiEchoLaserScan.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,263 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef float _angle_min_type;
+      _angle_min_type angle_min;
+      typedef float _angle_max_type;
+      _angle_max_type angle_max;
+      typedef float _angle_increment_type;
+      _angle_increment_type angle_increment;
+      typedef float _time_increment_type;
+      _time_increment_type time_increment;
+      typedef float _scan_time_type;
+      _scan_time_type scan_time;
+      typedef float _range_min_type;
+      _range_min_type range_min;
+      typedef float _range_max_type;
+      _range_max_type range_max;
+      uint32_t ranges_length;
+      typedef sensor_msgs::LaserEcho _ranges_type;
+      _ranges_type st_ranges;
+      _ranges_type * ranges;
+      uint32_t intensities_length;
+      typedef sensor_msgs::LaserEcho _intensities_type;
+      _intensities_type st_intensities;
+      _intensities_type * 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 + 0) = (this->ranges_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->ranges_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->ranges_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->ranges_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ranges_length);
+      for( uint32_t i = 0; i < ranges_length; i++){
+      offset += this->ranges[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->intensities_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->intensities_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->intensities_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->intensities_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->intensities_length);
+      for( uint32_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);
+      uint32_t ranges_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->ranges_length);
+      if(ranges_lengthT > ranges_length)
+        this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho));
+      ranges_length = ranges_lengthT;
+      for( uint32_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));
+      }
+      uint32_t intensities_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->intensities_length);
+      if(intensities_lengthT > intensities_length)
+        this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho));
+      intensities_length = intensities_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatFix.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,192 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef sensor_msgs::NavSatStatus _status_type;
+      _status_type status;
+      typedef double _latitude_type;
+      _latitude_type latitude;
+      typedef double _longitude_type;
+      _longitude_type longitude;
+      typedef double _altitude_type;
+      _altitude_type altitude;
+      double position_covariance[9];
+      typedef uint8_t _position_covariance_type_type;
+      _position_covariance_type_type 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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatStatus.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,73 @@
+#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:
+      typedef int8_t _status_type;
+      _status_type status;
+      typedef uint16_t _service_type;
+      _service_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t points_length;
+      typedef geometry_msgs::Point32 _points_type;
+      _points_type st_points;
+      _points_type * points;
+      uint32_t channels_length;
+      typedef sensor_msgs::ChannelFloat32 _channels_type;
+      _channels_type st_channels;
+      _channels_type * 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 + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->channels_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->channels_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->channels_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->channels_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->channels_length);
+      for( uint32_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);
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
+      points_length = points_lengthT;
+      for( uint32_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));
+      }
+      uint32_t channels_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->channels_length);
+      if(channels_lengthT > channels_length)
+        this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
+      channels_length = channels_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud2.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,185 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef uint32_t _height_type;
+      _height_type height;
+      typedef uint32_t _width_type;
+      _width_type width;
+      uint32_t fields_length;
+      typedef sensor_msgs::PointField _fields_type;
+      _fields_type st_fields;
+      _fields_type * fields;
+      typedef bool _is_bigendian_type;
+      _is_bigendian_type is_bigendian;
+      typedef uint32_t _point_step_type;
+      _point_step_type point_step;
+      typedef uint32_t _row_step_type;
+      _row_step_type row_step;
+      uint32_t data_length;
+      typedef uint8_t _data_type;
+      _data_type st_data;
+      _data_type * data;
+      typedef bool _is_dense_type;
+      _is_dense_type 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 + 0) = (this->fields_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->fields_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->fields_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->fields_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->fields_length);
+      for( uint32_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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t fields_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->fields_length);
+      if(fields_lengthT > fields_length)
+        this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
+      fields_length = fields_lengthT;
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointField.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef uint32_t _offset_type;
+      _offset_type offset;
+      typedef uint8_t _datatype_type;
+      _datatype_type datatype;
+      typedef uint32_t _count_type;
+      _count_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Range.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,149 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef uint8_t _radiation_type_type;
+      _radiation_type_type radiation_type;
+      typedef float _field_of_view_type;
+      _field_of_view_type field_of_view;
+      typedef float _min_range_type;
+      _min_range_type min_range;
+      typedef float _max_range_type;
+      _max_range_type max_range;
+      typedef float _range_type;
+      _range_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/RegionOfInterest.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef uint32_t _x_offset_type;
+      _x_offset_type x_offset;
+      typedef uint32_t _y_offset_type;
+      _y_offset_type y_offset;
+      typedef uint32_t _height_type;
+      _height_type height;
+      typedef uint32_t _width_type;
+      _width_type width;
+      typedef bool _do_rectify_type;
+      _do_rectify_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/RelativeHumidity.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _relative_humidity_type;
+      _relative_humidity_type relative_humidity;
+      typedef double _variance_type;
+      _variance_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/SetCameraInfo.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,111 @@
+#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:
+      typedef sensor_msgs::CameraInfo _camera_info_type;
+      _camera_info_type 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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _status_message_type;
+      _status_message_type 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);
+      varToArr(outbuffer + offset, length_status_message);
+      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;
+      arrToVar(length_status_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Temperature.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef double _temperature_type;
+      _temperature_type temperature;
+      typedef double _variance_type;
+      _variance_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/TimeReference.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,85 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef ros::Time _time_ref_type;
+      _time_ref_type time_ref;
+      typedef const char* _source_type;
+      _source_type 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);
+      varToArr(outbuffer + offset, length_source);
+      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;
+      arrToVar(length_source, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/Mesh.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,90 @@
+#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:
+      uint32_t triangles_length;
+      typedef shape_msgs::MeshTriangle _triangles_type;
+      _triangles_type st_triangles;
+      _triangles_type * triangles;
+      uint32_t vertices_length;
+      typedef geometry_msgs::Point _vertices_type;
+      _vertices_type st_vertices;
+      _vertices_type * vertices;
+
+    Mesh():
+      triangles_length(0), triangles(NULL),
+      vertices_length(0), vertices(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->triangles_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->triangles_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->triangles_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->triangles_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->triangles_length);
+      for( uint32_t i = 0; i < triangles_length; i++){
+      offset += this->triangles[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->vertices_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->vertices_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->vertices_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->vertices_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->vertices_length);
+      for( uint32_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;
+      uint32_t triangles_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      triangles_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      triangles_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      triangles_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->triangles_length);
+      if(triangles_lengthT > triangles_length)
+        this->triangles = (shape_msgs::MeshTriangle*)realloc(this->triangles, triangles_lengthT * sizeof(shape_msgs::MeshTriangle));
+      triangles_length = triangles_lengthT;
+      for( uint32_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));
+      }
+      uint32_t vertices_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      vertices_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->vertices_length);
+      if(vertices_lengthT > vertices_length)
+        this->vertices = (geometry_msgs::Point*)realloc(this->vertices, vertices_lengthT * sizeof(geometry_msgs::Point));
+      vertices_length = vertices_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/MeshTriangle.h	Sat Dec 31 00:48:34 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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/Plane.h	Sat Dec 31 00:48:34 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( uint32_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( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/shape_msgs/SolidPrimitive.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,109 @@
+#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:
+      typedef uint8_t _type_type;
+      _type_type type;
+      uint32_t dimensions_length;
+      typedef double _dimensions_type;
+      _dimensions_type st_dimensions;
+      _dimensions_type * 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 + 0) = (this->dimensions_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->dimensions_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->dimensions_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->dimensions_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->dimensions_length);
+      for( uint32_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);
+      uint32_t dimensions_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      dimensions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      dimensions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      dimensions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->dimensions_length);
+      if(dimensions_lengthT > dimensions_length)
+        this->dimensions = (double*)realloc(this->dimensions, dimensions_lengthT * sizeof(double));
+      dimensions_length = dimensions_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerInitialStatusCmd.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,109 @@
+#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:
+      typedef const char* _path_type;
+      _path_type path;
+      uint32_t initial_states_length;
+      typedef char* _initial_states_type;
+      _initial_states_type st_initial_states;
+      _initial_states_type * initial_states;
+      typedef const char* _local_data_type;
+      _local_data_type 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);
+      varToArr(outbuffer + offset, length_path);
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset + 0) = (this->initial_states_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->initial_states_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->initial_states_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->initial_states_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->initial_states_length);
+      for( uint32_t i = 0; i < initial_states_length; i++){
+      uint32_t length_initial_statesi = strlen(this->initial_states[i]);
+      varToArr(outbuffer + offset, length_initial_statesi);
+      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);
+      varToArr(outbuffer + offset, length_local_data);
+      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;
+      arrToVar(length_path, (inbuffer + offset));
+      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;
+      uint32_t initial_states_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->initial_states_length);
+      if(initial_states_lengthT > initial_states_length)
+        this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*));
+      initial_states_length = initial_states_lengthT;
+      for( uint32_t i = 0; i < initial_states_length; i++){
+      uint32_t length_st_initial_states;
+      arrToVar(length_st_initial_states, (inbuffer + offset));
+      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;
+      arrToVar(length_local_data, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerStatus.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,169 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _path_type;
+      _path_type path;
+      uint32_t initial_states_length;
+      typedef char* _initial_states_type;
+      _initial_states_type st_initial_states;
+      _initial_states_type * initial_states;
+      uint32_t active_states_length;
+      typedef char* _active_states_type;
+      _active_states_type st_active_states;
+      _active_states_type * active_states;
+      typedef const char* _local_data_type;
+      _local_data_type local_data;
+      typedef const char* _info_type;
+      _info_type 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);
+      varToArr(outbuffer + offset, length_path);
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset + 0) = (this->initial_states_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->initial_states_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->initial_states_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->initial_states_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->initial_states_length);
+      for( uint32_t i = 0; i < initial_states_length; i++){
+      uint32_t length_initial_statesi = strlen(this->initial_states[i]);
+      varToArr(outbuffer + offset, length_initial_statesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi);
+      offset += length_initial_statesi;
+      }
+      *(outbuffer + offset + 0) = (this->active_states_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->active_states_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->active_states_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->active_states_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->active_states_length);
+      for( uint32_t i = 0; i < active_states_length; i++){
+      uint32_t length_active_statesi = strlen(this->active_states[i]);
+      varToArr(outbuffer + offset, length_active_statesi);
+      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);
+      varToArr(outbuffer + offset, length_local_data);
+      offset += 4;
+      memcpy(outbuffer + offset, this->local_data, length_local_data);
+      offset += length_local_data;
+      uint32_t length_info = strlen(this->info);
+      varToArr(outbuffer + offset, length_info);
+      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;
+      arrToVar(length_path, (inbuffer + offset));
+      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;
+      uint32_t initial_states_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      initial_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->initial_states_length);
+      if(initial_states_lengthT > initial_states_length)
+        this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*));
+      initial_states_length = initial_states_lengthT;
+      for( uint32_t i = 0; i < initial_states_length; i++){
+      uint32_t length_st_initial_states;
+      arrToVar(length_st_initial_states, (inbuffer + offset));
+      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 active_states_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      active_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      active_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      active_states_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->active_states_length);
+      if(active_states_lengthT > active_states_length)
+        this->active_states = (char**)realloc(this->active_states, active_states_lengthT * sizeof(char*));
+      active_states_length = active_states_lengthT;
+      for( uint32_t i = 0; i < active_states_length; i++){
+      uint32_t length_st_active_states;
+      arrToVar(length_st_active_states, (inbuffer + offset));
+      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;
+      arrToVar(length_local_data, (inbuffer + offset));
+      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;
+      arrToVar(length_info, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/smach_msgs/SmachContainerStructure.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,246 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _path_type;
+      _path_type path;
+      uint32_t children_length;
+      typedef char* _children_type;
+      _children_type st_children;
+      _children_type * children;
+      uint32_t internal_outcomes_length;
+      typedef char* _internal_outcomes_type;
+      _internal_outcomes_type st_internal_outcomes;
+      _internal_outcomes_type * internal_outcomes;
+      uint32_t outcomes_from_length;
+      typedef char* _outcomes_from_type;
+      _outcomes_from_type st_outcomes_from;
+      _outcomes_from_type * outcomes_from;
+      uint32_t outcomes_to_length;
+      typedef char* _outcomes_to_type;
+      _outcomes_to_type st_outcomes_to;
+      _outcomes_to_type * outcomes_to;
+      uint32_t container_outcomes_length;
+      typedef char* _container_outcomes_type;
+      _container_outcomes_type st_container_outcomes;
+      _container_outcomes_type * 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);
+      varToArr(outbuffer + offset, length_path);
+      offset += 4;
+      memcpy(outbuffer + offset, this->path, length_path);
+      offset += length_path;
+      *(outbuffer + offset + 0) = (this->children_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->children_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->children_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->children_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->children_length);
+      for( uint32_t i = 0; i < children_length; i++){
+      uint32_t length_childreni = strlen(this->children[i]);
+      varToArr(outbuffer + offset, length_childreni);
+      offset += 4;
+      memcpy(outbuffer + offset, this->children[i], length_childreni);
+      offset += length_childreni;
+      }
+      *(outbuffer + offset + 0) = (this->internal_outcomes_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->internal_outcomes_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->internal_outcomes_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->internal_outcomes_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->internal_outcomes_length);
+      for( uint32_t i = 0; i < internal_outcomes_length; i++){
+      uint32_t length_internal_outcomesi = strlen(this->internal_outcomes[i]);
+      varToArr(outbuffer + offset, length_internal_outcomesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->internal_outcomes[i], length_internal_outcomesi);
+      offset += length_internal_outcomesi;
+      }
+      *(outbuffer + offset + 0) = (this->outcomes_from_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->outcomes_from_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->outcomes_from_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->outcomes_from_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->outcomes_from_length);
+      for( uint32_t i = 0; i < outcomes_from_length; i++){
+      uint32_t length_outcomes_fromi = strlen(this->outcomes_from[i]);
+      varToArr(outbuffer + offset, length_outcomes_fromi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->outcomes_from[i], length_outcomes_fromi);
+      offset += length_outcomes_fromi;
+      }
+      *(outbuffer + offset + 0) = (this->outcomes_to_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->outcomes_to_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->outcomes_to_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->outcomes_to_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->outcomes_to_length);
+      for( uint32_t i = 0; i < outcomes_to_length; i++){
+      uint32_t length_outcomes_toi = strlen(this->outcomes_to[i]);
+      varToArr(outbuffer + offset, length_outcomes_toi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->outcomes_to[i], length_outcomes_toi);
+      offset += length_outcomes_toi;
+      }
+      *(outbuffer + offset + 0) = (this->container_outcomes_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->container_outcomes_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->container_outcomes_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->container_outcomes_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->container_outcomes_length);
+      for( uint32_t i = 0; i < container_outcomes_length; i++){
+      uint32_t length_container_outcomesi = strlen(this->container_outcomes[i]);
+      varToArr(outbuffer + offset, length_container_outcomesi);
+      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;
+      arrToVar(length_path, (inbuffer + offset));
+      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;
+      uint32_t children_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      children_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      children_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      children_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->children_length);
+      if(children_lengthT > children_length)
+        this->children = (char**)realloc(this->children, children_lengthT * sizeof(char*));
+      children_length = children_lengthT;
+      for( uint32_t i = 0; i < children_length; i++){
+      uint32_t length_st_children;
+      arrToVar(length_st_children, (inbuffer + offset));
+      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*));
+      }
+      uint32_t internal_outcomes_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      internal_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      internal_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      internal_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->internal_outcomes_length);
+      if(internal_outcomes_lengthT > internal_outcomes_length)
+        this->internal_outcomes = (char**)realloc(this->internal_outcomes, internal_outcomes_lengthT * sizeof(char*));
+      internal_outcomes_length = internal_outcomes_lengthT;
+      for( uint32_t i = 0; i < internal_outcomes_length; i++){
+      uint32_t length_st_internal_outcomes;
+      arrToVar(length_st_internal_outcomes, (inbuffer + offset));
+      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*));
+      }
+      uint32_t outcomes_from_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      outcomes_from_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      outcomes_from_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      outcomes_from_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->outcomes_from_length);
+      if(outcomes_from_lengthT > outcomes_from_length)
+        this->outcomes_from = (char**)realloc(this->outcomes_from, outcomes_from_lengthT * sizeof(char*));
+      outcomes_from_length = outcomes_from_lengthT;
+      for( uint32_t i = 0; i < outcomes_from_length; i++){
+      uint32_t length_st_outcomes_from;
+      arrToVar(length_st_outcomes_from, (inbuffer + offset));
+      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*));
+      }
+      uint32_t outcomes_to_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      outcomes_to_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      outcomes_to_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      outcomes_to_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->outcomes_to_length);
+      if(outcomes_to_lengthT > outcomes_to_length)
+        this->outcomes_to = (char**)realloc(this->outcomes_to, outcomes_to_lengthT * sizeof(char*));
+      outcomes_to_length = outcomes_to_lengthT;
+      for( uint32_t i = 0; i < outcomes_to_length; i++){
+      uint32_t length_st_outcomes_to;
+      arrToVar(length_st_outcomes_to, (inbuffer + offset));
+      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*));
+      }
+      uint32_t container_outcomes_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      container_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      container_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      container_outcomes_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->container_outcomes_length);
+      if(container_outcomes_lengthT > container_outcomes_length)
+        this->container_outcomes = (char**)realloc(this->container_outcomes, container_outcomes_lengthT * sizeof(char*));
+      container_outcomes_length = container_outcomes_lengthT;
+      for( uint32_t i = 0; i < container_outcomes_length; i++){
+      uint32_t length_st_container_outcomes;
+      arrToVar(length_st_container_outcomes, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Bool.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef bool _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Byte.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef int8_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ByteMultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef int8_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Char.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,45 @@
+#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:
+      typedef uint8_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ColorRGBA.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,134 @@
+#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:
+      typedef float _r_type;
+      _r_type r;
+      typedef float _g_type;
+      _g_type g;
+      typedef float _b_type;
+      _b_type b;
+      typedef float _a_type;
+      _a_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Duration.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef ros::Duration _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Empty.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef float _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef float _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef double _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef double _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (double*)realloc(this->data, data_lengthT * sizeof(double));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Header.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,92 @@
+#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:
+      typedef uint32_t _seq_type;
+      _seq_type seq;
+      typedef ros::Time _stamp_type;
+      _stamp_type stamp;
+      typedef const char* _frame_id_type;
+      _frame_id_type 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);
+      varToArr(outbuffer + offset, length_frame_id);
+      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;
+      arrToVar(length_frame_id, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,58 @@
+#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:
+      typedef int16_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,84 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef int16_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef int32_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef int32_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,70 @@
+#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:
+      typedef int64_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,96 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef int64_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef int8_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,82 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef int8_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayDimension.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,81 @@
+#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:
+      typedef const char* _label_type;
+      _label_type label;
+      typedef uint32_t _size_type;
+      _size_type size;
+      typedef uint32_t _stride_type;
+      _stride_type stride;
+
+    MultiArrayDimension():
+      label(""),
+      size(0),
+      stride(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_label = strlen(this->label);
+      varToArr(outbuffer + offset, length_label);
+      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;
+      arrToVar(length_label, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayLayout.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,77 @@
+#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:
+      uint32_t dim_length;
+      typedef std_msgs::MultiArrayDimension _dim_type;
+      _dim_type st_dim;
+      _dim_type * dim;
+      typedef uint32_t _data_offset_type;
+      _data_offset_type data_offset;
+
+    MultiArrayLayout():
+      dim_length(0), dim(NULL),
+      data_offset(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->dim_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->dim_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->dim_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->dim_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->dim_length);
+      for( uint32_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;
+      uint32_t dim_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      dim_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->dim_length);
+      if(dim_lengthT > dim_length)
+        this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension));
+      dim_length = dim_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/String.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,55 @@
+#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:
+      typedef const char* _data_type;
+      _data_type data;
+
+    String():
+      data("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_data = strlen(this->data);
+      varToArr(outbuffer + offset, length_data);
+      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;
+      arrToVar(length_data, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Time.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef ros::Time _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,47 @@
+#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:
+      typedef uint16_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,73 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef uint16_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,51 @@
+#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:
+      typedef uint32_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,77 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef uint32_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,62 @@
+#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:
+      typedef uint64_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,88 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef uint64_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,45 @@
+#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:
+      typedef uint8_t _data_type;
+      _data_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8MultiArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,71 @@
+#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:
+      typedef std_msgs::MultiArrayLayout _layout_type;
+      _layout_type layout;
+      uint32_t data_length;
+      typedef uint8_t _data_type;
+      _data_type st_data;
+      _data_type * 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_srvs/Empty.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_srvs/SetBool.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,123 @@
+#ifndef _ROS_SERVICE_SetBool_h
+#define _ROS_SERVICE_SetBool_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_srvs
+{
+
+static const char SETBOOL[] = "std_srvs/SetBool";
+
+  class SetBoolRequest : public ros::Msg
+  {
+    public:
+      typedef bool _data_type;
+      _data_type data;
+
+    SetBoolRequest():
+      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 SETBOOL; };
+    const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; };
+
+  };
+
+  class SetBoolResponse : public ros::Msg
+  {
+    public:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _message_type;
+      _message_type message;
+
+    SetBoolResponse():
+      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);
+      varToArr(outbuffer + offset, length_message);
+      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;
+      arrToVar(length_message, (inbuffer + offset));
+      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 SETBOOL; };
+    const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; };
+
+  };
+
+  class SetBool {
+    public:
+    typedef SetBoolRequest Request;
+    typedef SetBoolResponse Response;
+  };
+
+}
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_srvs/Trigger.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,105 @@
+#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:
+      typedef bool _success_type;
+      _success_type success;
+      typedef const char* _message_type;
+      _message_type 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);
+      varToArr(outbuffer + offset, length_message);
+      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;
+      arrToVar(length_message, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/stereo_msgs/DisparityImage.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,176 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef sensor_msgs::Image _image_type;
+      _image_type image;
+      typedef float _f_type;
+      _f_type f;
+      typedef float _T_type;
+      _T_type T;
+      typedef sensor_msgs::RegionOfInterest _valid_window_type;
+      _valid_window_type valid_window;
+      typedef float _min_disparity_type;
+      _min_disparity_type min_disparity;
+      typedef float _max_disparity_type;
+      _max_disparity_type max_disparity;
+      typedef float _delta_d_type;
+      _delta_d_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/FrameGraph.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _dot_graph_type;
+      _dot_graph_type dot_graph;
+
+    FrameGraphResponse():
+      dot_graph("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_dot_graph = strlen(this->dot_graph);
+      varToArr(outbuffer + offset, length_dot_graph);
+      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;
+      arrToVar(length_dot_graph, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tf.h	Sat Dec 31 00:48:34 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
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tfMessage.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,64 @@
+#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:
+      uint32_t transforms_length;
+      typedef geometry_msgs::TransformStamped _transforms_type;
+      _transforms_type st_transforms;
+      _transforms_type * transforms;
+
+    tfMessage():
+      transforms_length(0), transforms(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->transforms_length);
+      for( uint32_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;
+      uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->transforms_length);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
+      transforms_length = transforms_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/transform_broadcaster.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,69 @@
+/* 
+ * 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 "ros.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
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/FrameGraph.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _frame_yaml_type;
+      _frame_yaml_type frame_yaml;
+
+    FrameGraphResponse():
+      frame_yaml("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_frame_yaml = strlen(this->frame_yaml);
+      varToArr(outbuffer + offset, length_frame_yaml);
+      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;
+      arrToVar(length_frame_yaml, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef tf2_msgs::LookupTransformActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef tf2_msgs::LookupTransformActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef tf2_msgs::LookupTransformActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef tf2_msgs::LookupTransformFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef tf2_msgs::LookupTransformGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef tf2_msgs::LookupTransformResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,178 @@
+#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:
+      typedef const char* _target_frame_type;
+      _target_frame_type target_frame;
+      typedef const char* _source_frame_type;
+      _source_frame_type source_frame;
+      typedef ros::Time _source_time_type;
+      _source_time_type source_time;
+      typedef ros::Duration _timeout_type;
+      _timeout_type timeout;
+      typedef ros::Time _target_time_type;
+      _target_time_type target_time;
+      typedef const char* _fixed_frame_type;
+      _fixed_frame_type fixed_frame;
+      typedef bool _advanced_type;
+      _advanced_type 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);
+      varToArr(outbuffer + offset, length_target_frame);
+      offset += 4;
+      memcpy(outbuffer + offset, this->target_frame, length_target_frame);
+      offset += length_target_frame;
+      uint32_t length_source_frame = strlen(this->source_frame);
+      varToArr(outbuffer + offset, length_source_frame);
+      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);
+      varToArr(outbuffer + offset, length_fixed_frame);
+      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;
+      arrToVar(length_target_frame, (inbuffer + offset));
+      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;
+      arrToVar(length_source_frame, (inbuffer + offset));
+      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;
+      arrToVar(length_fixed_frame, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/LookupTransformResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,50 @@
+#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:
+      typedef geometry_msgs::TransformStamped _transform_type;
+      _transform_type transform;
+      typedef tf2_msgs::TF2Error _error_type;
+      _error_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/TF2Error.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,69 @@
+#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:
+      typedef uint8_t _error_type;
+      _error_type error;
+      typedef const char* _error_string_type;
+      _error_string_type 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);
+      varToArr(outbuffer + offset, length_error_string);
+      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;
+      arrToVar(length_error_string, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf2_msgs/TFMessage.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,64 @@
+#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:
+      uint32_t transforms_length;
+      typedef geometry_msgs::TransformStamped _transforms_type;
+      _transforms_type st_transforms;
+      _transforms_type * transforms;
+
+    TFMessage():
+      transforms_length(0), transforms(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->transforms_length);
+      for( uint32_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;
+      uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->transforms_length);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
+      transforms_length = transforms_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/theora_image_transport/Packet.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,183 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t data_length;
+      typedef uint8_t _data_type;
+      _data_type st_data;
+      _data_type * data;
+      typedef int32_t _b_o_s_type;
+      _b_o_s_type b_o_s;
+      typedef int32_t _e_o_s_type;
+      _e_o_s_type e_o_s;
+      typedef int64_t _granulepos_type;
+      _granulepos_type granulepos;
+      typedef int64_t _packetno_type;
+      _packetno_type 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 + 0) = (this->data_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_length);
+      for( uint32_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);
+      uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->data_length);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      data_length = data_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/time.cpp	Sat Dec 31 00:48:34 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;
+  }
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxAdd.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    DemuxAddRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxDelete.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    DemuxDeleteRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxList.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,107 @@
+#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:
+      uint32_t topics_length;
+      typedef char* _topics_type;
+      _topics_type st_topics;
+      _topics_type * topics;
+
+    DemuxListResponse():
+      topics_length(0), topics(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->topics_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->topics_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->topics_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->topics_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->topics_length);
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      varToArr(outbuffer + offset, length_topicsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], length_topicsi);
+      offset += length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t topics_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->topics_length);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      topics_length = topics_lengthT;
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      arrToVar(length_st_topics, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/DemuxSelect.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,104 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    DemuxSelectRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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:
+      typedef const char* _prev_topic_type;
+      _prev_topic_type prev_topic;
+
+    DemuxSelectResponse():
+      prev_topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_prev_topic = strlen(this->prev_topic);
+      varToArr(outbuffer + offset, length_prev_topic);
+      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;
+      arrToVar(length_prev_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxAdd.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    MuxAddRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxDelete.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    MuxDeleteRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxList.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,107 @@
+#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:
+      uint32_t topics_length;
+      typedef char* _topics_type;
+      _topics_type st_topics;
+      _topics_type * topics;
+
+    MuxListResponse():
+      topics_length(0), topics(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->topics_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->topics_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->topics_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->topics_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->topics_length);
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_topicsi = strlen(this->topics[i]);
+      varToArr(outbuffer + offset, length_topicsi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], length_topicsi);
+      offset += length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t topics_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->topics_length);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      topics_length = topics_lengthT;
+      for( uint32_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics;
+      arrToVar(length_st_topics, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxSelect.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,104 @@
+#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:
+      typedef const char* _topic_type;
+      _topic_type topic;
+
+    MuxSelectRequest():
+      topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_topic = strlen(this->topic);
+      varToArr(outbuffer + offset, length_topic);
+      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;
+      arrToVar(length_topic, (inbuffer + offset));
+      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:
+      typedef const char* _prev_topic_type;
+      _prev_topic_type prev_topic;
+
+    MuxSelectResponse():
+      prev_topic("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_prev_topic = strlen(this->prev_topic);
+      varToArr(outbuffer + offset, length_prev_topic);
+      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;
+      arrToVar(length_prev_topic, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/JointTrajectory.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,107 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      uint32_t points_length;
+      typedef trajectory_msgs::JointTrajectoryPoint _points_type;
+      _points_type st_points;
+      _points_type * 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 + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_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);
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (trajectory_msgs::JointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::JointTrajectoryPoint));
+      points_length = points_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/JointTrajectoryPoint.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,270 @@
+#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:
+      uint32_t positions_length;
+      typedef double _positions_type;
+      _positions_type st_positions;
+      _positions_type * positions;
+      uint32_t velocities_length;
+      typedef double _velocities_type;
+      _velocities_type st_velocities;
+      _velocities_type * velocities;
+      uint32_t accelerations_length;
+      typedef double _accelerations_type;
+      _accelerations_type st_accelerations;
+      _accelerations_type * accelerations;
+      uint32_t effort_length;
+      typedef double _effort_type;
+      _effort_type st_effort;
+      _effort_type * effort;
+      typedef ros::Duration _time_from_start_type;
+      _time_from_start_type 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 + 0) = (this->positions_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->positions_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->positions_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->positions_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->positions_length);
+      for( uint32_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 + 0) = (this->velocities_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->velocities_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->velocities_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->velocities_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->velocities_length);
+      for( uint32_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 + 0) = (this->accelerations_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->accelerations_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->accelerations_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->accelerations_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->accelerations_length);
+      for( uint32_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 + 0) = (this->effort_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->effort_length);
+      for( uint32_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;
+      uint32_t positions_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->positions_length);
+      if(positions_lengthT > positions_length)
+        this->positions = (double*)realloc(this->positions, positions_lengthT * sizeof(double));
+      positions_length = positions_lengthT;
+      for( uint32_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));
+      }
+      uint32_t velocities_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->velocities_length);
+      if(velocities_lengthT > velocities_length)
+        this->velocities = (double*)realloc(this->velocities, velocities_lengthT * sizeof(double));
+      velocities_length = velocities_lengthT;
+      for( uint32_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));
+      }
+      uint32_t accelerations_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->accelerations_length);
+      if(accelerations_lengthT > accelerations_length)
+        this->accelerations = (double*)realloc(this->accelerations, accelerations_lengthT * sizeof(double));
+      accelerations_length = accelerations_lengthT;
+      for( uint32_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));
+      }
+      uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->effort_length);
+      if(effort_lengthT > effort_length)
+        this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
+      effort_length = effort_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/MultiDOFJointTrajectory.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,107 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      uint32_t joint_names_length;
+      typedef char* _joint_names_type;
+      _joint_names_type st_joint_names;
+      _joint_names_type * joint_names;
+      uint32_t points_length;
+      typedef trajectory_msgs::MultiDOFJointTrajectoryPoint _points_type;
+      _points_type st_points;
+      _points_type * 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 + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->joint_names_length);
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_joint_namesi = strlen(this->joint_names[i]);
+      varToArr(outbuffer + offset, length_joint_namesi);
+      offset += 4;
+      memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
+      offset += length_joint_namesi;
+      }
+      *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_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);
+      uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->joint_names_length);
+      if(joint_names_lengthT > joint_names_length)
+        this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
+      joint_names_length = joint_names_lengthT;
+      for( uint32_t i = 0; i < joint_names_length; i++){
+      uint32_t length_st_joint_names;
+      arrToVar(length_st_joint_names, (inbuffer + offset));
+      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*));
+      }
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (trajectory_msgs::MultiDOFJointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
+      points_length = points_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/trajectory_msgs/MultiDOFJointTrajectoryPoint.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,139 @@
+#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:
+      uint32_t transforms_length;
+      typedef geometry_msgs::Transform _transforms_type;
+      _transforms_type st_transforms;
+      _transforms_type * transforms;
+      uint32_t velocities_length;
+      typedef geometry_msgs::Twist _velocities_type;
+      _velocities_type st_velocities;
+      _velocities_type * velocities;
+      uint32_t accelerations_length;
+      typedef geometry_msgs::Twist _accelerations_type;
+      _accelerations_type st_accelerations;
+      _accelerations_type * accelerations;
+      typedef ros::Duration _time_from_start_type;
+      _time_from_start_type 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 + 0) = (this->transforms_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->transforms_length);
+      for( uint32_t i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->velocities_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->velocities_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->velocities_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->velocities_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->velocities_length);
+      for( uint32_t i = 0; i < velocities_length; i++){
+      offset += this->velocities[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->accelerations_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->accelerations_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->accelerations_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->accelerations_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->accelerations_length);
+      for( uint32_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;
+      uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->transforms_length);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
+      transforms_length = transforms_lengthT;
+      for( uint32_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));
+      }
+      uint32_t velocities_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->velocities_length);
+      if(velocities_lengthT > velocities_length)
+        this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
+      velocities_length = velocities_lengthT;
+      for( uint32_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));
+      }
+      uint32_t accelerations_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->accelerations_length);
+      if(accelerations_lengthT > accelerations_length)
+        this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
+      accelerations_length = accelerations_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeAction.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef turtle_actionlib::ShapeActionGoal _action_goal_type;
+      _action_goal_type action_goal;
+      typedef turtle_actionlib::ShapeActionResult _action_result_type;
+      _action_result_type action_result;
+      typedef turtle_actionlib::ShapeActionFeedback _action_feedback_type;
+      _action_feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef turtle_actionlib::ShapeFeedback _feedback_type;
+      _feedback_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalID _goal_id_type;
+      _goal_id_type goal_id;
+      typedef turtle_actionlib::ShapeGoal _goal_type;
+      _goal_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeActionResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,56 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef actionlib_msgs::GoalStatus _status_type;
+      _status_type status;
+      typedef turtle_actionlib::ShapeResult _result_type;
+      _result_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeFeedback.h	Sat Dec 31 00:48:34 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeGoal.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,86 @@
+#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:
+      typedef int32_t _edges_type;
+      _edges_type edges;
+      typedef float _radius_type;
+      _radius_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/ShapeResult.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,86 @@
+#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:
+      typedef float _interior_angle_type;
+      _interior_angle_type interior_angle;
+      typedef float _apothem_type;
+      _apothem_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtle_actionlib/Velocity.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,86 @@
+#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:
+      typedef float _linear_type;
+      _linear_type linear;
+      typedef float _angular_type;
+      _angular_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Color.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,59 @@
+#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:
+      typedef uint8_t _r_type;
+      _r_type r;
+      typedef uint8_t _g_type;
+      _g_type g;
+      typedef uint8_t _b_type;
+      _b_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Kill.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,87 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+
+    KillRequest():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Pose.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,158 @@
+#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:
+      typedef float _x_type;
+      _x_type x;
+      typedef float _y_type;
+      _y_type y;
+      typedef float _theta_type;
+      _theta_type theta;
+      typedef float _linear_velocity_type;
+      _linear_velocity_type linear_velocity;
+      typedef float _angular_velocity_type;
+      _angular_velocity_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/SetPen.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,105 @@
+#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:
+      typedef uint8_t _r_type;
+      _r_type r;
+      typedef uint8_t _g_type;
+      _g_type g;
+      typedef uint8_t _b_type;
+      _b_type b;
+      typedef uint8_t _width_type;
+      _width_type width;
+      typedef uint8_t _off_type;
+      _off_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/Spawn.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,176 @@
+#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:
+      typedef float _x_type;
+      _x_type x;
+      typedef float _y_type;
+      _y_type y;
+      typedef float _theta_type;
+      _theta_type theta;
+      typedef const char* _name_type;
+      _name_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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:
+      typedef const char* _name_type;
+      _name_type name;
+
+    SpawnResponse():
+      name("")
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t length_name = strlen(this->name);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/TeleportAbsolute.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,142 @@
+#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:
+      typedef float _x_type;
+      _x_type x;
+      typedef float _y_type;
+      _y_type y;
+      typedef float _theta_type;
+      _theta_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/turtlesim/TeleportRelative.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,118 @@
+#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:
+      typedef float _linear_type;
+      _linear_type linear;
+      typedef float _angular_type;
+      _angular_type 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/ImageMarker.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,262 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _ns_type;
+      _ns_type ns;
+      typedef int32_t _id_type;
+      _id_type id;
+      typedef int32_t _type_type;
+      _type_type type;
+      typedef int32_t _action_type;
+      _action_type action;
+      typedef geometry_msgs::Point _position_type;
+      _position_type position;
+      typedef float _scale_type;
+      _scale_type scale;
+      typedef std_msgs::ColorRGBA _outline_color_type;
+      _outline_color_type outline_color;
+      typedef uint8_t _filled_type;
+      _filled_type filled;
+      typedef std_msgs::ColorRGBA _fill_color_type;
+      _fill_color_type fill_color;
+      typedef ros::Duration _lifetime_type;
+      _lifetime_type lifetime;
+      uint32_t points_length;
+      typedef geometry_msgs::Point _points_type;
+      _points_type st_points;
+      _points_type * points;
+      uint32_t outline_colors_length;
+      typedef std_msgs::ColorRGBA _outline_colors_type;
+      _outline_colors_type st_outline_colors;
+      _outline_colors_type * 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);
+      varToArr(outbuffer + offset, length_ns);
+      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 + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->outline_colors_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->outline_colors_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->outline_colors_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->outline_colors_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->outline_colors_length);
+      for( uint32_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;
+      arrToVar(length_ns, (inbuffer + offset));
+      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);
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
+      points_length = points_lengthT;
+      for( uint32_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));
+      }
+      uint32_t outline_colors_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      outline_colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      outline_colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      outline_colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->outline_colors_length);
+      if(outline_colors_lengthT > outline_colors_length)
+        this->outline_colors = (std_msgs::ColorRGBA*)realloc(this->outline_colors, outline_colors_lengthT * sizeof(std_msgs::ColorRGBA));
+      outline_colors_length = outline_colors_lengthT;
+      for( uint32_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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarker.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,160 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef const char* _name_type;
+      _name_type name;
+      typedef const char* _description_type;
+      _description_type description;
+      typedef float _scale_type;
+      _scale_type scale;
+      uint32_t menu_entries_length;
+      typedef visualization_msgs::MenuEntry _menu_entries_type;
+      _menu_entries_type st_menu_entries;
+      _menu_entries_type * menu_entries;
+      uint32_t controls_length;
+      typedef visualization_msgs::InteractiveMarkerControl _controls_type;
+      _controls_type st_controls;
+      _controls_type * 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);
+      varToArr(outbuffer + offset, length_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, length_name);
+      offset += length_name;
+      uint32_t length_description = strlen(this->description);
+      varToArr(outbuffer + offset, length_description);
+      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 + 0) = (this->menu_entries_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->menu_entries_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->menu_entries_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->menu_entries_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->menu_entries_length);
+      for( uint32_t i = 0; i < menu_entries_length; i++){
+      offset += this->menu_entries[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->controls_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->controls_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->controls_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->controls_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->controls_length);
+      for( uint32_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;
+      arrToVar(length_name, (inbuffer + offset));
+      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;
+      arrToVar(length_description, (inbuffer + offset));
+      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);
+      uint32_t menu_entries_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      menu_entries_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      menu_entries_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      menu_entries_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->menu_entries_length);
+      if(menu_entries_lengthT > menu_entries_length)
+        this->menu_entries = (visualization_msgs::MenuEntry*)realloc(this->menu_entries, menu_entries_lengthT * sizeof(visualization_msgs::MenuEntry));
+      menu_entries_length = menu_entries_lengthT;
+      for( uint32_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));
+      }
+      uint32_t controls_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      controls_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      controls_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      controls_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->controls_length);
+      if(controls_lengthT > controls_length)
+        this->controls = (visualization_msgs::InteractiveMarkerControl*)realloc(this->controls, controls_lengthT * sizeof(visualization_msgs::InteractiveMarkerControl));
+      controls_length = controls_lengthT;
+      for( uint32_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 "dd86d22909d5a3364b384492e35c10af"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerControl.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,167 @@
+#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:
+      typedef const char* _name_type;
+      _name_type name;
+      typedef geometry_msgs::Quaternion _orientation_type;
+      _orientation_type orientation;
+      typedef uint8_t _orientation_mode_type;
+      _orientation_mode_type orientation_mode;
+      typedef uint8_t _interaction_mode_type;
+      _interaction_mode_type interaction_mode;
+      typedef bool _always_visible_type;
+      _always_visible_type always_visible;
+      uint32_t markers_length;
+      typedef visualization_msgs::Marker _markers_type;
+      _markers_type st_markers;
+      _markers_type * markers;
+      typedef bool _independent_marker_orientation_type;
+      _independent_marker_orientation_type independent_marker_orientation;
+      typedef const char* _description_type;
+      _description_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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 + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->markers_length);
+      for( uint32_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);
+      varToArr(outbuffer + offset, length_description);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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);
+      uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->markers_length);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
+      markers_length = markers_lengthT;
+      for( uint32_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;
+      arrToVar(length_description, (inbuffer + offset));
+      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 "b3c81e785788195d1840b86c28da1aac"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerFeedback.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,151 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _client_id_type;
+      _client_id_type client_id;
+      typedef const char* _marker_name_type;
+      _marker_name_type marker_name;
+      typedef const char* _control_name_type;
+      _control_name_type control_name;
+      typedef uint8_t _event_type_type;
+      _event_type_type event_type;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef uint32_t _menu_entry_id_type;
+      _menu_entry_id_type menu_entry_id;
+      typedef geometry_msgs::Point _mouse_point_type;
+      _mouse_point_type mouse_point;
+      typedef bool _mouse_point_valid_type;
+      _mouse_point_valid_type 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);
+      varToArr(outbuffer + offset, length_client_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->client_id, length_client_id);
+      offset += length_client_id;
+      uint32_t length_marker_name = strlen(this->marker_name);
+      varToArr(outbuffer + offset, length_marker_name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->marker_name, length_marker_name);
+      offset += length_marker_name;
+      uint32_t length_control_name = strlen(this->control_name);
+      varToArr(outbuffer + offset, length_control_name);
+      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;
+      arrToVar(length_client_id, (inbuffer + offset));
+      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;
+      arrToVar(length_marker_name, (inbuffer + offset));
+      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;
+      arrToVar(length_control_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerInit.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,105 @@
+#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:
+      typedef const char* _server_id_type;
+      _server_id_type server_id;
+      typedef uint64_t _seq_num_type;
+      _seq_num_type seq_num;
+      uint32_t markers_length;
+      typedef visualization_msgs::InteractiveMarker _markers_type;
+      _markers_type st_markers;
+      _markers_type * 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);
+      varToArr(outbuffer + offset, length_server_id);
+      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->markers_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->markers_length);
+      for( uint32_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;
+      arrToVar(length_server_id, (inbuffer + offset));
+      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);
+      uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->markers_length);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker));
+      markers_length = markers_lengthT;
+      for( uint32_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 "d5f2c5045a72456d228676ab91048734"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerPose.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,67 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef const char* _name_type;
+      _name_type 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);
+      varToArr(outbuffer + offset, length_name);
+      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;
+      arrToVar(length_name, (inbuffer + offset));
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/InteractiveMarkerUpdate.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,177 @@
+#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:
+      typedef const char* _server_id_type;
+      _server_id_type server_id;
+      typedef uint64_t _seq_num_type;
+      _seq_num_type seq_num;
+      typedef uint8_t _type_type;
+      _type_type type;
+      uint32_t markers_length;
+      typedef visualization_msgs::InteractiveMarker _markers_type;
+      _markers_type st_markers;
+      _markers_type * markers;
+      uint32_t poses_length;
+      typedef visualization_msgs::InteractiveMarkerPose _poses_type;
+      _poses_type st_poses;
+      _poses_type * poses;
+      uint32_t erases_length;
+      typedef char* _erases_type;
+      _erases_type st_erases;
+      _erases_type * 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);
+      varToArr(outbuffer + offset, length_server_id);
+      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 + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->markers_length);
+      for( uint32_t i = 0; i < markers_length; i++){
+      offset += this->markers[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->poses_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->poses_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->poses_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->poses_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->poses_length);
+      for( uint32_t i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->erases_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->erases_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->erases_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->erases_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->erases_length);
+      for( uint32_t i = 0; i < erases_length; i++){
+      uint32_t length_erasesi = strlen(this->erases[i]);
+      varToArr(outbuffer + offset, length_erasesi);
+      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;
+      arrToVar(length_server_id, (inbuffer + offset));
+      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);
+      uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->markers_length);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker));
+      markers_length = markers_lengthT;
+      for( uint32_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));
+      }
+      uint32_t poses_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->poses_length);
+      if(poses_lengthT > poses_length)
+        this->poses = (visualization_msgs::InteractiveMarkerPose*)realloc(this->poses, poses_lengthT * sizeof(visualization_msgs::InteractiveMarkerPose));
+      poses_length = poses_lengthT;
+      for( uint32_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));
+      }
+      uint32_t erases_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      erases_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      erases_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      erases_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->erases_length);
+      if(erases_lengthT > erases_length)
+        this->erases = (char**)realloc(this->erases, erases_lengthT * sizeof(char*));
+      erases_length = erases_lengthT;
+      for( uint32_t i = 0; i < erases_length; i++){
+      uint32_t length_st_erases;
+      arrToVar(length_st_erases, (inbuffer + offset));
+      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 "710d308d0a9276d65945e92dd30b3946"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/Marker.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,312 @@
+#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:
+      typedef std_msgs::Header _header_type;
+      _header_type header;
+      typedef const char* _ns_type;
+      _ns_type ns;
+      typedef int32_t _id_type;
+      _id_type id;
+      typedef int32_t _type_type;
+      _type_type type;
+      typedef int32_t _action_type;
+      _action_type action;
+      typedef geometry_msgs::Pose _pose_type;
+      _pose_type pose;
+      typedef geometry_msgs::Vector3 _scale_type;
+      _scale_type scale;
+      typedef std_msgs::ColorRGBA _color_type;
+      _color_type color;
+      typedef ros::Duration _lifetime_type;
+      _lifetime_type lifetime;
+      typedef bool _frame_locked_type;
+      _frame_locked_type frame_locked;
+      uint32_t points_length;
+      typedef geometry_msgs::Point _points_type;
+      _points_type st_points;
+      _points_type * points;
+      uint32_t colors_length;
+      typedef std_msgs::ColorRGBA _colors_type;
+      _colors_type st_colors;
+      _colors_type * colors;
+      typedef const char* _text_type;
+      _text_type text;
+      typedef const char* _mesh_resource_type;
+      _mesh_resource_type mesh_resource;
+      typedef bool _mesh_use_embedded_materials_type;
+      _mesh_use_embedded_materials_type 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 };
+      enum { DELETEALL = 3 };
+
+    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);
+      varToArr(outbuffer + offset, length_ns);
+      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 + 0) = (this->points_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->points_length);
+      for( uint32_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->colors_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->colors_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->colors_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->colors_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->colors_length);
+      for( uint32_t i = 0; i < colors_length; i++){
+      offset += this->colors[i].serialize(outbuffer + offset);
+      }
+      uint32_t length_text = strlen(this->text);
+      varToArr(outbuffer + offset, length_text);
+      offset += 4;
+      memcpy(outbuffer + offset, this->text, length_text);
+      offset += length_text;
+      uint32_t length_mesh_resource = strlen(this->mesh_resource);
+      varToArr(outbuffer + offset, length_mesh_resource);
+      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;
+      arrToVar(length_ns, (inbuffer + offset));
+      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);
+      uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->points_length);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
+      points_length = points_lengthT;
+      for( uint32_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));
+      }
+      uint32_t colors_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->colors_length);
+      if(colors_lengthT > colors_length)
+        this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA));
+      colors_length = colors_lengthT;
+      for( uint32_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;
+      arrToVar(length_text, (inbuffer + offset));
+      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;
+      arrToVar(length_mesh_resource, (inbuffer + offset));
+      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 "4048c9de2a16f4ae8e0538085ebf1b97"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/MarkerArray.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,64 @@
+#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:
+      uint32_t markers_length;
+      typedef visualization_msgs::Marker _markers_type;
+      _markers_type st_markers;
+      _markers_type * markers;
+
+    MarkerArray():
+      markers_length(0), markers(NULL)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->markers_length);
+      for( uint32_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 markers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
+      markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
+      offset += sizeof(this->markers_length);
+      if(markers_lengthT > markers_length)
+        this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
+      markers_length = markers_lengthT;
+      for( uint32_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 "d155b9ce5188fbaf89745847fd5882d7"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/visualization_msgs/MenuEntry.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,108 @@
+#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:
+      typedef uint32_t _id_type;
+      _id_type id;
+      typedef uint32_t _parent_id_type;
+      _parent_id_type parent_id;
+      typedef const char* _title_type;
+      _title_type title;
+      typedef const char* _command_type;
+      _command_type command;
+      typedef uint8_t _command_type_type;
+      _command_type_type 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);
+      varToArr(outbuffer + offset, length_title);
+      offset += 4;
+      memcpy(outbuffer + offset, this->title, length_title);
+      offset += length_title;
+      uint32_t length_command = strlen(this->command);
+      varToArr(outbuffer + offset, length_command);
+      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;
+      arrToVar(length_title, (inbuffer + offset));
+      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;
+      arrToVar(length_command, (inbuffer + offset));
+      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