diff --git a/cr/docs/cr.robotin.maxref.xml b/cr/docs/cr.robotin.maxref.xml
new file mode 100755
index 0000000000000000000000000000000000000000..f113d57d976c8d06455109dbf0e695b450e941fe
--- /dev/null
+++ b/cr/docs/cr.robotin.maxref.xml
@@ -0,0 +1,98 @@
+
+
+
+
+
+
+
+ Robotics Operating System (ROS) Turtlebot3 Burger Inputs (Reader).
+
+
+
+
+ Receives ROS messages (Velocity, Odometry, Laser Scan, IMU, Sensors State, Joints State, Transformation) from Turtlebot3 Robot via ROS Messages.
+
+
+
+
+ Creative Robotics Lab
+ CR
+ ROS
+ Robotics
+ Turtlebot3
+
+
+
+
+
+ Messages: Open, Close
+
+
+
+
+
+
+ Input data from the TurtleBot3 robot
+ Further description in http://emanual.robotis.com/docs/en/platform/turtlebot3/overview/
+
+
+
+
+
+
+ Enter the robot IP.
+
+
+
+
+
+
+ Velocities (linear, angular) data
+ The linear/translational speed (x,y,z in m/s) and angular/rotational speed (x,y,z in rad/s) of the robot. Full details: http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html
+
+
+ Odometry data
+ The Turtlebot3’s odometry information based on the encoder and IMU. Odometry is the use of data from motion sensors to estimate change in position over time. It estimates the robot position relative to a starting location. It measures how many times the wheels have rotated, and by multiplying with the circumference of its wheels, computes the distance. Data include position (x,y,z), orientation (x,y,z,w), linear speed (x,y,z), and angular speed (x,y,z). Full details: http://docs.ros.org/kinetic/api/nav_msgs/html/msg/Odometry.html
+
+
+ Laser Scan data
+ The scan values of the LiDAR mounted on top of the Turtlebot3. The Laser Distance Sensor LDS-01 is a 2D laser scanner capable of sensing 360 degrees that collects a set of data around the robot to use for SLAM (Simultaneous Localization and Mapping) and Navigation. Detection distance: 12 cm ~ 350 cm. Sampling Rate: 1.8kHz. Full details: http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html
+
+
+ Inertial Measurement Unit (IMU) data
+ Inertial measurement unit (IMU) is a combination of Accelerometers, Gyroscopes, and Magnetometer. Estimate the robot's orientation (x,y,z,w), angular/rotational velocity (x,y,z) in rad/sec, and linear acceleration (x,y,z) in m/s^2. Full details: http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html
+
+
+ Sensors State data
+ Turtlebot3 Sensors state: button status, voltage level, encoder values. Full details: https://github.com/ROBOTIS-GIT/turtlebot3_msgs/blob/master/msg/SensorState.msg
+
+
+ Joints State data
+ The state of a set of torque controlled joints (left wheel/right wheel). Full details: http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html
+
+
+ Transformation data
+ The transform from base_link to imu_link. It defines where the IMU sensor is mounted relative to the robot's chassis so that the sensor readings can be correctly transformed into the robot's frame of reference. This transform should be static; the IMU frame moves and rotates together with the robot frame, so relative position of IMU frame does not change. Data include translation (x,y,z) and rotation (x,y,z,w). Full details: http://docs.ros.org/api/tf/html/msg/tfMessage.html
+
+
+
+
+
+
+
+ Open a connection to the robot
+
+
+
+
+ Close the connection to the robot
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/cr/docs/cr.robotout.maxref.xml b/cr/docs/cr.robotout.maxref.xml
new file mode 100755
index 0000000000000000000000000000000000000000..87388d34f59b72099369fb5933e02b482d07cdfd
--- /dev/null
+++ b/cr/docs/cr.robotout.maxref.xml
@@ -0,0 +1,78 @@
+
+
+
+
+
+
+
+ Robotics Operating System (ROS) Turtlebot3 Burger Outputs (Writer).
+
+
+
+
+ Send Velocities (Linear, Angular) to Turtlebot3 Robot via ROS Messages.
+
+
+
+
+ Creative Robotics Lab
+ CR
+ ROS
+ Robotics
+ Turtlebot3
+
+
+
+
+
+ Messages: Open, Close, Break, Bang
+
+
+ Send data to robot, as specified in Turtlebot3: http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html
+ Control the linear/translational speed (x,y,z in m/s) and angular/rotational speed (x,y,z in rad/s) of the robot. Further description in http://emanual.robotis.com/docs/en/platform/turtlebot3/overview/
+
+
+
+
+
+
+
+
+
+ Enter the robot IP.
+
+
+
+
+
+
+
+
+
+
+ Open a connection to the robot
+
+
+
+
+ Close the connection to the robot
+
+
+
+
+ Send the velocities message to the robot
+
+
+
+
+ Send a break (zero velocities) message to the robot
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/cr/externals/cr.boardout.mxo/Contents/MacOS/cr.boardout b/cr/externals/cr.boardout.mxo/Contents/MacOS/cr.boardout
index 5da69fd119e16238214af16f754656c60f1cb67a..9bf140bc4a7d74aad6840a3d936720966de55fce 100755
Binary files a/cr/externals/cr.boardout.mxo/Contents/MacOS/cr.boardout and b/cr/externals/cr.boardout.mxo/Contents/MacOS/cr.boardout differ
diff --git a/cr/externals/cr.robotin.mxo/Contents/Info.plist b/cr/externals/cr.robotin.mxo/Contents/Info.plist
new file mode 100644
index 0000000000000000000000000000000000000000..bfdb212aafdb15203c52fbeb98aec35f6cebd947
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Info.plist
@@ -0,0 +1,44 @@
+
+
+
+
+ BuildMachineOSBuild
+ 16G1314
+ CFBundleDevelopmentRegion
+ English
+ CFBundleExecutable
+ cr.robotin
+ CFBundleInfoDictionaryVersion
+ 7.0.1
+ CFBundleLongVersionString
+ cr.robotin 7.0.1, Copyright 2014 Cycling '74
+ CFBundlePackageType
+ iLaX
+ CFBundleShortVersionString
+ 7.0.1
+ CFBundleSignature
+ max2
+ CFBundleSupportedPlatforms
+
+ MacOSX
+
+ CFBundleVersion
+ 7.0.1
+ CSResourcesFileMapped
+
+ DTCompiler
+ com.apple.compilers.llvm.clang.1_0
+ DTPlatformBuild
+ 8E3004b
+ DTPlatformVersion
+ GM
+ DTSDKBuild
+ 16E185
+ DTSDKName
+ macosx10.12
+ DTXcode
+ 0833
+ DTXcodeBuild
+ 8E3004b
+
+
diff --git a/cr/externals/cr.robotin.mxo/Contents/MacOS/cr.robotin b/cr/externals/cr.robotin.mxo/Contents/MacOS/cr.robotin
new file mode 100755
index 0000000000000000000000000000000000000000..d083a3c8fa2c032dea789c639aa666afcfefcb0f
Binary files /dev/null and b/cr/externals/cr.robotin.mxo/Contents/MacOS/cr.robotin differ
diff --git a/cr/externals/cr.robotin.mxo/Contents/PkgInfo b/cr/externals/cr.robotin.mxo/Contents/PkgInfo
new file mode 100644
index 0000000000000000000000000000000000000000..0febb6eb9eebdfa768ac5563c31e92629c7a71ab
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/PkgInfo
@@ -0,0 +1 @@
+iLaXmax2
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..4a6042d1e2e4b8b518e721535c64b629753a2c2f
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestAction_h
+#define _ROS_actionlib_TestAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..aab52afa6b766d5a1914bb0b809cb19c9407c886
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestActionFeedback_h
+#define _ROS_actionlib_TestActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..6cb740255cd2206e07a30b30ddee71bfbf944194
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestActionGoal_h
+#define _ROS_actionlib_TestActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..d534d0ac6bb7be28dee15ece12e847a9a893f927
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestActionResult_h
+#define _ROS_actionlib_TestActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..83798cfd667f0d183001a120b00901b3996a65ea
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestFeedback.h
@@ -0,0 +1,62 @@
+#ifndef _ROS_actionlib_TestFeedback_h
+#define _ROS_actionlib_TestFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..40d3a99bf09012210685fe356ec31479881aa6ff
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestGoal.h
@@ -0,0 +1,62 @@
+#ifndef _ROS_actionlib_TestGoal_h
+#define _ROS_actionlib_TestGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..52a2fe9c76042a9a7b95466c4460e64497ecc5f8
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestRequestAction_h
+#define _ROS_actionlib_TestRequestAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..0d585c0c2eb66a90ad6554e48a0c1fb0e9f2b2da
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestRequestActionFeedback_h
+#define _ROS_actionlib_TestRequestActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..24c6c4873c56feaf9f12641443e95dd557416e3a
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestRequestActionGoal_h
+#define _ROS_actionlib_TestRequestActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..a71e715af33a32f9f133d83aed12f3a8c079cbaf
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TestRequestActionResult_h
+#define _ROS_actionlib_TestRequestActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..f1fc24796db62f1505a4b34ad733ce8530261ae1
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestFeedback.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_actionlib_TestRequestFeedback_h
+#define _ROS_actionlib_TestRequestFeedback_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+ class TestRequestFeedback : public ros::Msg
+ {
+ public:
+
+ TestRequestFeedback()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "actionlib/TestRequestFeedback"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..321ebd31dd50a51d5535d4768d089fd2b9cdf85a
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestGoal.h
@@ -0,0 +1,215 @@
+#ifndef _ROS_actionlib_TestRequestGoal_h
+#define _ROS_actionlib_TestRequestGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..97887253a38fb9a4fd34781b69ec9d86371ccd4e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestRequestResult.h
@@ -0,0 +1,80 @@
+#ifndef _ROS_actionlib_TestRequestResult_h
+#define _ROS_actionlib_TestRequestResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..5c9718c93420a89c67c4593345a4b42a3092fb4e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TestResult.h
@@ -0,0 +1,62 @@
+#ifndef _ROS_actionlib_TestResult_h
+#define _ROS_actionlib_TestResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..30c73cc9e1baa5f049f2ddfed062d85b08b87199
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TwoIntsAction_h
+#define _ROS_actionlib_TwoIntsAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..8cd4862fa04dc2fc63c5de31f90f8d2bb315f3bf
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TwoIntsActionFeedback_h
+#define _ROS_actionlib_TwoIntsActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..7d33c178e992bd70886c1c55113a98a3c7c9fe36
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TwoIntsActionGoal_h
+#define _ROS_actionlib_TwoIntsActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..e36c808fe5c1825e51eddc0e1eb51f4b6bce6e21
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_TwoIntsActionResult_h
+#define _ROS_actionlib_TwoIntsActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..3789c4dcd8515d892575dfd08c4a1775a3f0a8de
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsFeedback.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_actionlib_TwoIntsFeedback_h
+#define _ROS_actionlib_TwoIntsFeedback_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace actionlib
+{
+
+ class TwoIntsFeedback : public ros::Msg
+ {
+ public:
+
+ TwoIntsFeedback()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "actionlib/TwoIntsFeedback"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..088c6ec3e44b437a116275e0ab4f83b0bef06c07
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsGoal.h
@@ -0,0 +1,102 @@
+#ifndef _ROS_actionlib_TwoIntsGoal_h
+#define _ROS_actionlib_TwoIntsGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..51d3cce117fbfdda46ca849c54c076f2c1ccd9ba
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib/TwoIntsResult.h
@@ -0,0 +1,70 @@
+#ifndef _ROS_actionlib_TwoIntsResult_h
+#define _ROS_actionlib_TwoIntsResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalID.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalID.h
new file mode 100644
index 0000000000000000000000000000000000000000..24391a3e87bff4310514346601667becd9c0000e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalID.h
@@ -0,0 +1,79 @@
+#ifndef _ROS_actionlib_msgs_GoalID_h
+#define _ROS_actionlib_msgs_GoalID_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatus.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatus.h
new file mode 100644
index 0000000000000000000000000000000000000000..349524c3a935d8ff0570d407373c3e7ccca353d7
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatus.h
@@ -0,0 +1,78 @@
+#ifndef _ROS_actionlib_msgs_GoalStatus_h
+#define _ROS_actionlib_msgs_GoalStatus_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatusArray.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatusArray.h
new file mode 100644
index 0000000000000000000000000000000000000000..9e39b5f845a39019cd8fd58bf4ba49cd97a45854
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_msgs/GoalStatusArray.h
@@ -0,0 +1,70 @@
+#ifndef _ROS_actionlib_msgs_GoalStatusArray_h
+#define _ROS_actionlib_msgs_GoalStatusArray_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..16eef59a9284fadd87a7b404b93b4a3e7e0fca40
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_AveragingAction_h
+#define _ROS_actionlib_tutorials_AveragingAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..e269f39d2baac0f75e40a45550f8859e219cdc87
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionFeedback_h
+#define _ROS_actionlib_tutorials_AveragingActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..e9f718ff814ab411a806e8e599be705f838d350d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionGoal_h
+#define _ROS_actionlib_tutorials_AveragingActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..db99e51744122f79d4fcff69945c38235e51343c
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_AveragingActionResult_h
+#define _ROS_actionlib_tutorials_AveragingActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..e71ad1f0682e9e8f92c1beed7203fba59d0a2181
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingFeedback.h
@@ -0,0 +1,134 @@
+#ifndef _ROS_actionlib_tutorials_AveragingFeedback_h
+#define _ROS_actionlib_tutorials_AveragingFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..e1cc2ad30300c9c3ef71097facf35a02b4db9a4d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingGoal.h
@@ -0,0 +1,62 @@
+#ifndef _ROS_actionlib_tutorials_AveragingGoal_h
+#define _ROS_actionlib_tutorials_AveragingGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..e476e594205cedf0daecf247281b218ffb11c648
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/AveragingResult.h
@@ -0,0 +1,86 @@
+#ifndef _ROS_actionlib_tutorials_AveragingResult_h
+#define _ROS_actionlib_tutorials_AveragingResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..2fd1c636d52a49896640f93f2b3c6afe25ec6244
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciAction_h
+#define _ROS_actionlib_tutorials_FibonacciAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..241ebad304c32ead12da8eab99cd600207ab58f9
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionFeedback_h
+#define _ROS_actionlib_tutorials_FibonacciActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..dd1361794f2e177c698d7be1ee764aa2f2c5f4b9
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionGoal_h
+#define _ROS_actionlib_tutorials_FibonacciActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..35c9d48c53e61ab072dab9f9c3a453d4a2e73bdf
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciActionResult_h
+#define _ROS_actionlib_tutorials_FibonacciActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..87eaf8fa71158f56d1e0aef1fd2792033c708e85
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciFeedback.h
@@ -0,0 +1,82 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciFeedback_h
+#define _ROS_actionlib_tutorials_FibonacciFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..e711de10bf8b534544eecee3a0f1946b9d345a4c
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciGoal.h
@@ -0,0 +1,62 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciGoal_h
+#define _ROS_actionlib_tutorials_FibonacciGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..dc710239d0f034bf6af44caeae9a25d8d45eaaeb
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/actionlib_tutorials/FibonacciResult.h
@@ -0,0 +1,82 @@
+#ifndef _ROS_actionlib_tutorials_FibonacciResult_h
+#define _ROS_actionlib_tutorials_FibonacciResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/base_local_planner/Position2DInt.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/base_local_planner/Position2DInt.h
new file mode 100644
index 0000000000000000000000000000000000000000..79beed25ad6d3686cf7eed2d0455863d05f97b5a
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/base_local_planner/Position2DInt.h
@@ -0,0 +1,102 @@
+#ifndef _ROS_base_local_planner_Position2DInt_h
+#define _ROS_base_local_planner_Position2DInt_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace base_local_planner
+{
+
+ class Position2DInt : public ros::Msg
+ {
+ public:
+ typedef int64_t _x_type;
+ _x_type x;
+ typedef int64_t _y_type;
+ _y_type y;
+
+ Position2DInt():
+ x(0),
+ y(0)
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ union {
+ int64_t 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 {
+ int64_t real;
+ uint64_t base;
+ } u_y;
+ u_y.real = this->y;
+ *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+ *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+ *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+ *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+ *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
+ *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
+ *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
+ *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
+ offset += sizeof(this->y);
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ union {
+ int64_t 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 {
+ int64_t real;
+ uint64_t base;
+ } u_y;
+ u_y.base = 0;
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
+ u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
+ this->y = u_y.real;
+ offset += sizeof(this->y);
+ return offset;
+ }
+
+ const char * getType(){ return "base_local_planner/Position2DInt"; };
+ const char * getMD5(){ return "3b834ede922a0fff22c43585c533b49f"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Constants.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Constants.h
new file mode 100644
index 0000000000000000000000000000000000000000..9594342f62f1b3cda9bc743bcdf04cb6c4a69217
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Constants.h
@@ -0,0 +1,44 @@
+#ifndef _ROS_bond_Constants_h
+#define _ROS_bond_Constants_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace bond
+{
+
+ class Constants : public ros::Msg
+ {
+ public:
+ enum { DEAD_PUBLISH_PERIOD = 0.05 };
+ enum { DEFAULT_CONNECT_TIMEOUT = 10.0 };
+ enum { DEFAULT_HEARTBEAT_TIMEOUT = 4.0 };
+ enum { DEFAULT_DISCONNECT_TIMEOUT = 2.0 };
+ enum { DEFAULT_HEARTBEAT_PERIOD = 1.0 };
+ enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout };
+
+ Constants()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "bond/Constants"; };
+ const char * getMD5(){ return "6fc594dc1d7bd7919077042712f8c8b0"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Status.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Status.h
new file mode 100644
index 0000000000000000000000000000000000000000..b9fa9a5484bb6dffb37e8252605f3c769186689f
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/bond/Status.h
@@ -0,0 +1,144 @@
+#ifndef _ROS_bond_Status_h
+#define _ROS_bond_Status_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..ec67771ad20f89dd11949574e0529a39e35de879
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryAction_h
+#define _ROS_control_msgs_FollowJointTrajectoryAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..d5d037a75ff917a6c3ec027e1f1fee8e40174a8e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..4aa00c6466386c37e775dd0231b6578def6f0a39
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionGoal_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..aa6b2b3f9126e21ecb097bc0f2b6381e13e367ac
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryActionResult_h
+#define _ROS_control_msgs_FollowJointTrajectoryActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..6f27eccc9615209bea284219616d9d044a3b2f35
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryFeedback.h
@@ -0,0 +1,97 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryFeedback_h
+#define _ROS_control_msgs_FollowJointTrajectoryFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..1185615ab3e4e6aa493fb04046e4180047dad372
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryGoal.h
@@ -0,0 +1,119 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryGoal_h
+#define _ROS_control_msgs_FollowJointTrajectoryGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..819f27265783893ac4844ee7bc36dbaaea7d3299
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/FollowJointTrajectoryResult.h
@@ -0,0 +1,85 @@
+#ifndef _ROS_control_msgs_FollowJointTrajectoryResult_h
+#define _ROS_control_msgs_FollowJointTrajectoryResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommand.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommand.h
new file mode 100644
index 0000000000000000000000000000000000000000..0b37e5c4f007962922ffff9cdc2c1fcad4c2d9ad
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommand.h
@@ -0,0 +1,102 @@
+#ifndef _ROS_control_msgs_GripperCommand_h
+#define _ROS_control_msgs_GripperCommand_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..68d8356e00af1a7200f6bbbd101a6fdfd34ecf0d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_GripperCommandAction_h
+#define _ROS_control_msgs_GripperCommandAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..67f99c9c1b0d3e4d62a7e0d069e85fb2d1191de4
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_GripperCommandActionFeedback_h
+#define _ROS_control_msgs_GripperCommandActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..efb19d1d8e90ee1c35e1bf46cacad720cef176c0
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_GripperCommandActionGoal_h
+#define _ROS_control_msgs_GripperCommandActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..704f18db86b87b781cb3042736f81c9b9fc9e424
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_GripperCommandActionResult_h
+#define _ROS_control_msgs_GripperCommandActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..15d0397b4f6a94a6b3b4b114f98faf6bcaccf700
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandFeedback.h
@@ -0,0 +1,138 @@
+#ifndef _ROS_control_msgs_GripperCommandFeedback_h
+#define _ROS_control_msgs_GripperCommandFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..544a864749da9aba26022127edc6a835f4866a34
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandGoal.h
@@ -0,0 +1,44 @@
+#ifndef _ROS_control_msgs_GripperCommandGoal_h
+#define _ROS_control_msgs_GripperCommandGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..e28b26016feaf8649a9558ae6110e38e8f3dfaa0
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/GripperCommandResult.h
@@ -0,0 +1,138 @@
+#ifndef _ROS_control_msgs_GripperCommandResult_h
+#define _ROS_control_msgs_GripperCommandResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointControllerState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointControllerState.h
new file mode 100644
index 0000000000000000000000000000000000000000..b70ef6d2fb228acdcc90c2ca713f7da0f085509d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointControllerState.h
@@ -0,0 +1,382 @@
+#ifndef _ROS_control_msgs_JointControllerState_h
+#define _ROS_control_msgs_JointControllerState_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTolerance.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTolerance.h
new file mode 100644
index 0000000000000000000000000000000000000000..051971eea27ac02358bfb543a622dd635f337038
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTolerance.h
@@ -0,0 +1,151 @@
+#ifndef _ROS_control_msgs_JointTolerance_h
+#define _ROS_control_msgs_JointTolerance_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..96bbaa488b1686516ebea2e894139b651943b3ac
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_JointTrajectoryAction_h
+#define _ROS_control_msgs_JointTrajectoryAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..8df7fee09150195e67aab627eded53ee440df4ec
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionFeedback_h
+#define _ROS_control_msgs_JointTrajectoryActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..8c432bb5ae7458cfc6490faad9c4d3915495af9f
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionGoal_h
+#define _ROS_control_msgs_JointTrajectoryActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..2a11d224d36cd8b5341c79a371ceeecf97ee824d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_JointTrajectoryActionResult_h
+#define _ROS_control_msgs_JointTrajectoryActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryControllerState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryControllerState.h
new file mode 100644
index 0000000000000000000000000000000000000000..148db3a7900e5c1d65bbd9047d6ab3d4e9fa1363
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryControllerState.h
@@ -0,0 +1,97 @@
+#ifndef _ROS_control_msgs_JointTrajectoryControllerState_h
+#define _ROS_control_msgs_JointTrajectoryControllerState_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..9dfe808d1ad01bfeb70ddfcf3902fa36fad650f5
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryFeedback.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_JointTrajectoryFeedback_h
+#define _ROS_control_msgs_JointTrajectoryFeedback_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+ class JointTrajectoryFeedback : public ros::Msg
+ {
+ public:
+
+ JointTrajectoryFeedback()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "control_msgs/JointTrajectoryFeedback"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..b699132e456fedba7acef0d08063bfe885fe772e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryGoal.h
@@ -0,0 +1,44 @@
+#ifndef _ROS_control_msgs_JointTrajectoryGoal_h
+#define _ROS_control_msgs_JointTrajectoryGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..623ed9cd099c212a6be65d4d93450b096de4d6d4
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/JointTrajectoryResult.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_JointTrajectoryResult_h
+#define _ROS_control_msgs_JointTrajectoryResult_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+ class JointTrajectoryResult : public ros::Msg
+ {
+ public:
+
+ JointTrajectoryResult()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "control_msgs/JointTrajectoryResult"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PidState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PidState.h
new file mode 100644
index 0000000000000000000000000000000000000000..a19ddf9739a643532eb894b8e544eafef46f8ed9
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PidState.h
@@ -0,0 +1,420 @@
+#ifndef _ROS_control_msgs_PidState_h
+#define _ROS_control_msgs_PidState_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..82ee446909a212585ae198b9842d4e8dcc6fc6e8
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_PointHeadAction_h
+#define _ROS_control_msgs_PointHeadAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..780656b1de51f13a0114903f138582a487aec0c3
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_PointHeadActionFeedback_h
+#define _ROS_control_msgs_PointHeadActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..12ae7911bedd1f3cd4c6e032e5e37c68f7b31997
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_PointHeadActionGoal_h
+#define _ROS_control_msgs_PointHeadActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..7708fe60379fb43a4a3002871dfcf7ac01689c9d
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_PointHeadActionResult_h
+#define _ROS_control_msgs_PointHeadActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..beafd3ef52939c8a44e8323d1e2284c8b52d8857
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadFeedback.h
@@ -0,0 +1,70 @@
+#ifndef _ROS_control_msgs_PointHeadFeedback_h
+#define _ROS_control_msgs_PointHeadFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..4d7355cbdea878a4b77632d5ec9e169ab7320747
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadGoal.h
@@ -0,0 +1,123 @@
+#ifndef _ROS_control_msgs_PointHeadGoal_h
+#define _ROS_control_msgs_PointHeadGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..53f789e92946eeba57f8825f09422dd6fc4d5b83
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/PointHeadResult.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_PointHeadResult_h
+#define _ROS_control_msgs_PointHeadResult_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+ class PointHeadResult : public ros::Msg
+ {
+ public:
+
+ PointHeadResult()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "control_msgs/PointHeadResult"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryCalibrationState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryCalibrationState.h
new file mode 100644
index 0000000000000000000000000000000000000000..0fd1a66a0be9f04857c28b0ab83f4147ba73788e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryCalibrationState.h
@@ -0,0 +1,88 @@
+#ifndef _ROS_SERVICE_QueryCalibrationState_h
+#define _ROS_SERVICE_QueryCalibrationState_h
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryTrajectoryState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryTrajectoryState.h
new file mode 100644
index 0000000000000000000000000000000000000000..aef19a80e64436c1c8851f3d5344b841ece4a8ab
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/QueryTrajectoryState.h
@@ -0,0 +1,287 @@
+#ifndef _ROS_SERVICE_QueryTrajectoryState_h
+#define _ROS_SERVICE_QueryTrajectoryState_h
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionAction.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionAction.h
new file mode 100644
index 0000000000000000000000000000000000000000..3117ee131ddcb6691577837cf716e9570c7e4742
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionAction.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_SingleJointPositionAction_h
+#define _ROS_control_msgs_SingleJointPositionAction_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..82cba63dd233a10c8b46d9727a2ba46d226c038e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionFeedback.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionFeedback_h
+#define _ROS_control_msgs_SingleJointPositionActionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..75c789880add2c65d89920a2b69f97df1cbb2c89
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionGoal.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionGoal_h
+#define _ROS_control_msgs_SingleJointPositionActionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..ef99cd8ff3a1db8c3648312f9c13b9255bb0dd3e
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionActionResult.h
@@ -0,0 +1,56 @@
+#ifndef _ROS_control_msgs_SingleJointPositionActionResult_h
+#define _ROS_control_msgs_SingleJointPositionActionResult_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionFeedback.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionFeedback.h
new file mode 100644
index 0000000000000000000000000000000000000000..cbf8fa4dc0b4ff3a630157bbf11bcfd6f92bca06
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionFeedback.h
@@ -0,0 +1,140 @@
+#ifndef _ROS_control_msgs_SingleJointPositionFeedback_h
+#define _ROS_control_msgs_SingleJointPositionFeedback_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionGoal.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionGoal.h
new file mode 100644
index 0000000000000000000000000000000000000000..7261176297aea0181e9c8e4eb3178d0555b7cbc0
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionGoal.h
@@ -0,0 +1,126 @@
+#ifndef _ROS_control_msgs_SingleJointPositionGoal_h
+#define _ROS_control_msgs_SingleJointPositionGoal_h
+
+#include
+#include
+#include
+#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
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionResult.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionResult.h
new file mode 100644
index 0000000000000000000000000000000000000000..7593425910d62bd10c7958e2eb57e86705111ef9
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_msgs/SingleJointPositionResult.h
@@ -0,0 +1,38 @@
+#ifndef _ROS_control_msgs_SingleJointPositionResult_h
+#define _ROS_control_msgs_SingleJointPositionResult_h
+
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace control_msgs
+{
+
+ class SingleJointPositionResult : public ros::Msg
+ {
+ public:
+
+ SingleJointPositionResult()
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ return offset;
+ }
+
+ const char * getType(){ return "control_msgs/SingleJointPositionResult"; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+}
+#endif
\ No newline at end of file
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_toolbox/SetPidGains.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_toolbox/SetPidGains.h
new file mode 100644
index 0000000000000000000000000000000000000000..709d825d139dc7e2147243584c72469d780eb502
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/control_toolbox/SetPidGains.h
@@ -0,0 +1,216 @@
+#ifndef _ROS_SERVICE_SetPidGains_h
+#define _ROS_SERVICE_SetPidGains_h
+#include
+#include
+#include
+#include "ros/msg.h"
+
+namespace control_toolbox
+{
+
+static const char SETPIDGAINS[] = "control_toolbox/SetPidGains";
+
+ class SetPidGainsRequest : public ros::Msg
+ {
+ public:
+ 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;
+
+ SetPidGainsRequest():
+ p(0),
+ i(0),
+ d(0),
+ i_clamp(0),
+ antiwindup(0)
+ {
+ }
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ 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;
+ 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 SETPIDGAINS; };
+ const char * getMD5(){ return "4a43159879643e60937bf2893b633607"; };
+
+ };
+
+ class SetPidGainsResponse : public ros::Msg
+ {
+ public:
+
+ SetPidGainsResponse()
+ {
+ }
+
+ 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 SETPIDGAINS; };
+ const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+ };
+
+ class SetPidGains {
+ public:
+ typedef SetPidGainsRequest Request;
+ typedef SetPidGainsResponse Response;
+ };
+
+}
+#endif
diff --git a/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/controller_manager_msgs/ControllerState.h b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/controller_manager_msgs/ControllerState.h
new file mode 100644
index 0000000000000000000000000000000000000000..ea728c4ee7e7cd9b12c7db0f82a13ca9a2653434
--- /dev/null
+++ b/cr/externals/cr.robotin.mxo/Contents/Resources/ros_lib/controller_manager_msgs/ControllerState.h
@@ -0,0 +1,115 @@
+#ifndef _ROS_controller_manager_msgs_ControllerState_h
+#define _ROS_controller_manager_msgs_ControllerState_h
+
+#include
+#include
+#include