rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
Revision 0:30537dec6e0b, committed 2015-02-15
- Comitter:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Commit message:
- First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MODSERIAL.lib Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/AjK/code/MODSERIAL/#ae0408ebdd68
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MbedHardware.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +/* + * MbedHardware + * + * Created on: Aug 17, 2011 + * Author: nucho + */ + +#ifndef MBEDHARDWARE_H_ +#define MBEDHARDWARE_H_ + +#include"mbed.h" +#include"MODSERIAL.h" + +#ifndef ROSSERIAL_BAUDRATE +#define ROSSERIAL_BAUDRATE 57600 +#endif + + +class MbedHardware { +public: + MbedHardware(MODSERIAL* io, int baud= ROSSERIAL_BAUDRATE):iostream(*io){ + baud_ = baud; + t.start(); + } + MbedHardware():iostream(USBTX, USBRX) { + baud_ = ROSSERIAL_BAUDRATE; + t.start(); + } + MbedHardware(MbedHardware& h):iostream(h.iostream) { + this->baud_ = h.baud_; + + t.start(); + } + + void setBaud(int baud) { + this->baud_= baud; + } + + int getBaud() { + return baud_; + } + + void init() { + iostream.baud(baud_); + } + + int read() { + if (iostream.readable()) { + return iostream.getc(); + } else { + return -1; + } + }; + void write(uint8_t* data, int length) { + for (int i=0; i<length; i++) iostream.putc(data[i]); + } + + unsigned long time() { + return t.read_ms(); + } + +protected: + int baud_; + MODSERIAL iostream; + Timer t; +}; + + +#endif /* MBEDHARDWARE_H_ */ \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestAction_h +#define _ROS_actionlib_TestAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib/TestActionGoal.h" +#include "actionlib/TestActionResult.h" +#include "actionlib/TestActionFeedback.h" + +namespace actionlib +{ + + class TestAction : public ros::Msg + { + public: + actionlib::TestActionGoal action_goal; + actionlib::TestActionResult action_result; + actionlib::TestActionFeedback action_feedback; + + TestAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestAction"; }; + const char * getMD5(){ return "991e87a72802262dfbe5d1b3cf6efc9a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestActionFeedback_h +#define _ROS_actionlib_TestActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestFeedback.h" + +namespace actionlib +{ + + class TestActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TestFeedback feedback; + + TestActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestActionFeedback"; }; + const char * getMD5(){ return "6d3d0bf7fb3dda24779c010a9f3eb7cb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestActionGoal_h +#define _ROS_actionlib_TestActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TestGoal.h" + +namespace actionlib +{ + + class TestActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + actionlib::TestGoal goal; + + TestActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestActionGoal"; }; + const char * getMD5(){ return "348369c5b403676156094e8c159720bf"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestActionResult_h +#define _ROS_actionlib_TestActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestResult.h" + +namespace actionlib +{ + + class TestActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TestResult result; + + TestActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestActionResult"; }; + const char * getMD5(){ return "3d669e3a63aa986c667ea7b0f46ce85e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_actionlib_TestFeedback_h +#define _ROS_actionlib_TestFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TestFeedback : public ros::Msg + { + public: + int32_t feedback; + + TestFeedback(): + feedback(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_feedback; + u_feedback.real = this->feedback; + *(outbuffer + offset + 0) = (u_feedback.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_feedback.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_feedback.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_feedback.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->feedback); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_feedback; + u_feedback.base = 0; + u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->feedback = u_feedback.real; + offset += sizeof(this->feedback); + return offset; + } + + const char * getType(){ return "actionlib/TestFeedback"; }; + const char * getMD5(){ return "49ceb5b32ea3af22073ede4a0328249e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_actionlib_TestGoal_h +#define _ROS_actionlib_TestGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TestGoal : public ros::Msg + { + public: + int32_t goal; + + TestGoal(): + goal(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_goal; + u_goal.real = this->goal; + *(outbuffer + offset + 0) = (u_goal.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_goal.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_goal.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_goal.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->goal); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_goal; + u_goal.base = 0; + u_goal.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_goal.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_goal.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_goal.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->goal = u_goal.real; + offset += sizeof(this->goal); + return offset; + } + + const char * getType(){ return "actionlib/TestGoal"; }; + const char * getMD5(){ return "18df0149936b7aa95588e3862476ebde"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestRequestAction_h +#define _ROS_actionlib_TestRequestAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib/TestRequestActionGoal.h" +#include "actionlib/TestRequestActionResult.h" +#include "actionlib/TestRequestActionFeedback.h" + +namespace actionlib +{ + + class TestRequestAction : public ros::Msg + { + public: + actionlib::TestRequestActionGoal action_goal; + actionlib::TestRequestActionResult action_result; + actionlib::TestRequestActionFeedback action_feedback; + + TestRequestAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestAction"; }; + const char * getMD5(){ return "dc44b1f4045dbf0d1db54423b3b86b30"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestRequestActionFeedback_h +#define _ROS_actionlib_TestRequestActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestRequestFeedback.h" + +namespace actionlib +{ + + class TestRequestActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TestRequestFeedback feedback; + + TestRequestActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestRequestActionGoal_h +#define _ROS_actionlib_TestRequestActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TestRequestGoal.h" + +namespace actionlib +{ + + class TestRequestActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + actionlib::TestRequestGoal goal; + + TestRequestActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestActionGoal"; }; + const char * getMD5(){ return "1889556d3fef88f821c7cb004e4251f3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TestRequestActionResult_h +#define _ROS_actionlib_TestRequestActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestRequestResult.h" + +namespace actionlib +{ + + class TestRequestActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TestRequestResult result; + + TestRequestActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestActionResult"; }; + const char * getMD5(){ return "0476d1fdf437a3a6e7d6d0e9f5561298"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_actionlib_TestRequestFeedback_h +#define _ROS_actionlib_TestRequestFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TestRequestFeedback : public ros::Msg + { + public: + + TestRequestFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "actionlib/TestRequestFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,207 @@ +#ifndef _ROS_actionlib_TestRequestGoal_h +#define _ROS_actionlib_TestRequestGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace actionlib +{ + + class TestRequestGoal : public ros::Msg + { + public: + int32_t terminate_status; + bool ignore_cancel; + const char* result_text; + int32_t the_result; + bool is_simple_client; + ros::Duration delay_accept; + ros::Duration delay_terminate; + ros::Duration pause_status; + enum { TERMINATE_SUCCESS = 0 }; + enum { TERMINATE_ABORTED = 1 }; + enum { TERMINATE_REJECTED = 2 }; + enum { TERMINATE_LOSE = 3 }; + enum { TERMINATE_DROP = 4 }; + enum { TERMINATE_EXCEPTION = 5 }; + + TestRequestGoal(): + terminate_status(0), + ignore_cancel(0), + result_text(""), + the_result(0), + is_simple_client(0), + delay_accept(), + delay_terminate(), + pause_status() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_terminate_status; + u_terminate_status.real = this->terminate_status; + *(outbuffer + offset + 0) = (u_terminate_status.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_terminate_status.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_terminate_status.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_terminate_status.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->terminate_status); + union { + bool real; + uint8_t base; + } u_ignore_cancel; + u_ignore_cancel.real = this->ignore_cancel; + *(outbuffer + offset + 0) = (u_ignore_cancel.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ignore_cancel); + uint32_t length_result_text = strlen(this->result_text); + memcpy(outbuffer + offset, &length_result_text, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->result_text, length_result_text); + offset += length_result_text; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.real = this->the_result; + *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_client; + u_is_simple_client.real = this->is_simple_client; + *(outbuffer + offset + 0) = (u_is_simple_client.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_simple_client); + *(outbuffer + offset + 0) = (this->delay_accept.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_accept.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_accept.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_accept.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_accept.sec); + *(outbuffer + offset + 0) = (this->delay_accept.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_accept.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_accept.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_accept.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_accept.nsec); + *(outbuffer + offset + 0) = (this->delay_terminate.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_terminate.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_terminate.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_terminate.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_terminate.sec); + *(outbuffer + offset + 0) = (this->delay_terminate.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_terminate.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_terminate.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_terminate.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_terminate.nsec); + *(outbuffer + offset + 0) = (this->pause_status.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->pause_status.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->pause_status.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->pause_status.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->pause_status.sec); + *(outbuffer + offset + 0) = (this->pause_status.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->pause_status.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->pause_status.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->pause_status.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->pause_status.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_terminate_status; + u_terminate_status.base = 0; + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->terminate_status = u_terminate_status.real; + offset += sizeof(this->terminate_status); + union { + bool real; + uint8_t base; + } u_ignore_cancel; + u_ignore_cancel.base = 0; + u_ignore_cancel.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ignore_cancel = u_ignore_cancel.real; + offset += sizeof(this->ignore_cancel); + uint32_t length_result_text; + memcpy(&length_result_text, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_result_text; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_result_text-1]=0; + this->result_text = (char *)(inbuffer + offset-1); + offset += length_result_text; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.base = 0; + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->the_result = u_the_result.real; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_client; + u_is_simple_client.base = 0; + u_is_simple_client.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_simple_client = u_is_simple_client.real; + offset += sizeof(this->is_simple_client); + this->delay_accept.sec = ((uint32_t) (*(inbuffer + offset))); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_accept.sec); + this->delay_accept.nsec = ((uint32_t) (*(inbuffer + offset))); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_accept.nsec); + this->delay_terminate.sec = ((uint32_t) (*(inbuffer + offset))); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_terminate.sec); + this->delay_terminate.nsec = ((uint32_t) (*(inbuffer + offset))); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_terminate.nsec); + this->pause_status.sec = ((uint32_t) (*(inbuffer + offset))); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->pause_status.sec); + this->pause_status.nsec = ((uint32_t) (*(inbuffer + offset))); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->pause_status.nsec); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestGoal"; }; + const char * getMD5(){ return "db5d00ba98302d6c6dd3737e9a03ceea"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestRequestResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_actionlib_TestRequestResult_h +#define _ROS_actionlib_TestRequestResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TestRequestResult : public ros::Msg + { + public: + int32_t the_result; + bool is_simple_server; + + TestRequestResult(): + the_result(0), + is_simple_server(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.real = this->the_result; + *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_server; + u_is_simple_server.real = this->is_simple_server; + *(outbuffer + offset + 0) = (u_is_simple_server.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_simple_server); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.base = 0; + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->the_result = u_the_result.real; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_server; + u_is_simple_server.base = 0; + u_is_simple_server.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_simple_server = u_is_simple_server.real; + offset += sizeof(this->is_simple_server); + return offset; + } + + const char * getType(){ return "actionlib/TestRequestResult"; }; + const char * getMD5(){ return "61c2364524499c7c5017e2f3fce7ba06"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TestResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_actionlib_TestResult_h +#define _ROS_actionlib_TestResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TestResult : public ros::Msg + { + public: + int32_t result; + + TestResult(): + result(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result; + u_result.real = this->result; + *(outbuffer + offset + 0) = (u_result.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_result.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_result.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_result.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->result); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result; + u_result.base = 0; + u_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->result = u_result.real; + offset += sizeof(this->result); + return offset; + } + + const char * getType(){ return "actionlib/TestResult"; }; + const char * getMD5(){ return "034a8e20d6a306665e3a5b340fab3f09"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TwoIntsAction_h +#define _ROS_actionlib_TwoIntsAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib/TwoIntsActionGoal.h" +#include "actionlib/TwoIntsActionResult.h" +#include "actionlib/TwoIntsActionFeedback.h" + +namespace actionlib +{ + + class TwoIntsAction : public ros::Msg + { + public: + actionlib::TwoIntsActionGoal action_goal; + actionlib::TwoIntsActionResult action_result; + actionlib::TwoIntsActionFeedback action_feedback; + + TwoIntsAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsAction"; }; + const char * getMD5(){ return "6d1aa538c4bd6183a2dfb7fcac41ee50"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TwoIntsActionFeedback_h +#define _ROS_actionlib_TwoIntsActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TwoIntsFeedback.h" + +namespace actionlib +{ + + class TwoIntsActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TwoIntsFeedback feedback; + + TwoIntsActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TwoIntsActionGoal_h +#define _ROS_actionlib_TwoIntsActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TwoIntsGoal.h" + +namespace actionlib +{ + + class TwoIntsActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + actionlib::TwoIntsGoal goal; + + TwoIntsActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsActionGoal"; }; + const char * getMD5(){ return "684a2db55d6ffb8046fb9d6764ce0860"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_TwoIntsActionResult_h +#define _ROS_actionlib_TwoIntsActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TwoIntsResult.h" + +namespace actionlib +{ + + class TwoIntsActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib::TwoIntsResult result; + + TwoIntsActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsActionResult"; }; + const char * getMD5(){ return "3ba7dea8b8cddcae4528ade4ef74b6e7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_actionlib_TwoIntsFeedback_h +#define _ROS_actionlib_TwoIntsFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsFeedback : public ros::Msg + { + public: + + TwoIntsFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,100 @@ +#ifndef _ROS_actionlib_TwoIntsGoal_h +#define _ROS_actionlib_TwoIntsGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsGoal : public ros::Msg + { + public: + int64_t a; + int64_t b; + + TwoIntsGoal(): + a(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->b); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->a = u_a.real; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->b = u_b.real; + offset += sizeof(this->b); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsGoal"; }; + const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib/TwoIntsResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_actionlib_TwoIntsResult_h +#define _ROS_actionlib_TwoIntsResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsResult : public ros::Msg + { + public: + int64_t sum; + + TwoIntsResult(): + sum(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.real = this->sum; + *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->sum); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.base = 0; + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->sum = u_sum.real; + offset += sizeof(this->sum); + return offset; + } + + const char * getType(){ return "actionlib/TwoIntsResult"; }; + const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_msgs/GoalID.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_actionlib_msgs_GoalID_h +#define _ROS_actionlib_msgs_GoalID_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace actionlib_msgs +{ + + class GoalID : public ros::Msg + { + public: + ros::Time stamp; + const char* id; + + GoalID(): + stamp(), + id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + return offset; + } + + const char * getType(){ return "actionlib_msgs/GoalID"; }; + const char * getMD5(){ return "302881f31927c1df708a2dbab0e80ee8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_msgs/GoalStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,75 @@ +#ifndef _ROS_actionlib_msgs_GoalStatus_h +#define _ROS_actionlib_msgs_GoalStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib_msgs/GoalID.h" + +namespace actionlib_msgs +{ + + class GoalStatus : public ros::Msg + { + public: + actionlib_msgs::GoalID goal_id; + uint8_t status; + const char* text; + enum { PENDING = 0 }; + enum { ACTIVE = 1 }; + enum { PREEMPTED = 2 }; + enum { SUCCEEDED = 3 }; + enum { ABORTED = 4 }; + enum { REJECTED = 5 }; + enum { PREEMPTING = 6 }; + enum { RECALLING = 7 }; + enum { RECALLED = 8 }; + enum { LOST = 9 }; + + GoalStatus(): + goal_id(), + status(0), + text("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->goal_id.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->status >> (8 * 0)) & 0xFF; + offset += sizeof(this->status); + uint32_t length_text = strlen(this->text); + memcpy(outbuffer + offset, &length_text, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->text, length_text); + offset += length_text; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->goal_id.deserialize(inbuffer + offset); + this->status = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->status); + uint32_t length_text; + memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_text; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_text-1]=0; + this->text = (char *)(inbuffer + offset-1); + offset += length_text; + return offset; + } + + const char * getType(){ return "actionlib_msgs/GoalStatus"; }; + const char * getMD5(){ return "d388f9b87b3c471f784434d671988d4a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_msgs/GoalStatusArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_actionlib_msgs_GoalStatusArray_h +#define _ROS_actionlib_msgs_GoalStatusArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" + +namespace actionlib_msgs +{ + + class GoalStatusArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t status_list_length; + actionlib_msgs::GoalStatus st_status_list; + actionlib_msgs::GoalStatus * status_list; + + GoalStatusArray(): + header(), + status_list_length(0), status_list(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = status_list_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < status_list_length; i++){ + offset += this->status_list[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t status_list_lengthT = *(inbuffer + offset++); + if(status_list_lengthT > status_list_length) + this->status_list = (actionlib_msgs::GoalStatus*)realloc(this->status_list, status_list_lengthT * sizeof(actionlib_msgs::GoalStatus)); + offset += 3; + status_list_length = status_list_lengthT; + for( uint8_t i = 0; i < status_list_length; i++){ + offset += this->st_status_list.deserialize(inbuffer + offset); + memcpy( &(this->status_list[i]), &(this->st_status_list), sizeof(actionlib_msgs::GoalStatus)); + } + return offset; + } + + const char * getType(){ return "actionlib_msgs/GoalStatusArray"; }; + const char * getMD5(){ return "8b2b82f13216d0a8ea88bd3af735e619"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_AveragingAction_h +#define _ROS_actionlib_tutorials_AveragingAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib_tutorials/AveragingActionGoal.h" +#include "actionlib_tutorials/AveragingActionResult.h" +#include "actionlib_tutorials/AveragingActionFeedback.h" + +namespace actionlib_tutorials +{ + + class AveragingAction : public ros::Msg + { + public: + actionlib_tutorials::AveragingActionGoal action_goal; + actionlib_tutorials::AveragingActionResult action_result; + actionlib_tutorials::AveragingActionFeedback action_feedback; + + AveragingAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingAction"; }; + const char * getMD5(){ return "628678f2b4fa6a5951746a4a2d39e716"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionFeedback_h +#define _ROS_actionlib_tutorials_AveragingActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/AveragingFeedback.h" + +namespace actionlib_tutorials +{ + + class AveragingActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib_tutorials::AveragingFeedback feedback; + + AveragingActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingActionFeedback"; }; + const char * getMD5(){ return "78a4a09241b1791069223ae7ebd5b16b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionGoal_h +#define _ROS_actionlib_tutorials_AveragingActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib_tutorials/AveragingGoal.h" + +namespace actionlib_tutorials +{ + + class AveragingActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + actionlib_tutorials::AveragingGoal goal; + + AveragingActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingActionGoal"; }; + const char * getMD5(){ return "1561825b734ebd6039851c501e3fb570"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionResult_h +#define _ROS_actionlib_tutorials_AveragingActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/AveragingResult.h" + +namespace actionlib_tutorials +{ + + class AveragingActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib_tutorials::AveragingResult result; + + AveragingActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingActionResult"; }; + const char * getMD5(){ return "8672cb489d347580acdcd05c5d497497"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,130 @@ +#ifndef _ROS_actionlib_tutorials_AveragingFeedback_h +#define _ROS_actionlib_tutorials_AveragingFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingFeedback : public ros::Msg + { + public: + int32_t sample; + float data; + float mean; + float std_dev; + + AveragingFeedback(): + sample(0), + data(0), + mean(0), + std_dev(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_sample; + u_sample.real = this->sample; + *(outbuffer + offset + 0) = (u_sample.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sample.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sample.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sample.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sample); + union { + float real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + union { + float real; + uint32_t base; + } u_mean; + u_mean.real = this->mean; + *(outbuffer + offset + 0) = (u_mean.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_mean.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_mean.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_mean.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean); + union { + float real; + uint32_t base; + } u_std_dev; + u_std_dev.real = this->std_dev; + *(outbuffer + offset + 0) = (u_std_dev.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_std_dev.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_std_dev.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_std_dev.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->std_dev); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_sample; + u_sample.base = 0; + u_sample.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_sample.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_sample.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_sample.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->sample = u_sample.real; + offset += sizeof(this->sample); + union { + float real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + union { + float real; + uint32_t base; + } u_mean; + u_mean.base = 0; + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->mean = u_mean.real; + offset += sizeof(this->mean); + union { + float real; + uint32_t base; + } u_std_dev; + u_std_dev.base = 0; + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->std_dev = u_std_dev.real; + offset += sizeof(this->std_dev); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingFeedback"; }; + const char * getMD5(){ return "9e8dfc53c2f2a032ca33fa80ec46fd4f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_actionlib_tutorials_AveragingGoal_h +#define _ROS_actionlib_tutorials_AveragingGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingGoal : public ros::Msg + { + public: + int32_t samples; + + AveragingGoal(): + samples(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_samples; + u_samples.real = this->samples; + *(outbuffer + offset + 0) = (u_samples.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_samples.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_samples.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_samples.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->samples); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_samples; + u_samples.base = 0; + u_samples.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_samples.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_samples.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_samples.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->samples = u_samples.real; + offset += sizeof(this->samples); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingGoal"; }; + const char * getMD5(){ return "32c9b10ef9b253faa93b93f564762c8f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/AveragingResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_actionlib_tutorials_AveragingResult_h +#define _ROS_actionlib_tutorials_AveragingResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingResult : public ros::Msg + { + public: + float mean; + float std_dev; + + AveragingResult(): + mean(0), + std_dev(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_mean; + u_mean.real = this->mean; + *(outbuffer + offset + 0) = (u_mean.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_mean.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_mean.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_mean.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean); + union { + float real; + uint32_t base; + } u_std_dev; + u_std_dev.real = this->std_dev; + *(outbuffer + offset + 0) = (u_std_dev.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_std_dev.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_std_dev.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_std_dev.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->std_dev); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_mean; + u_mean.base = 0; + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_mean.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->mean = u_mean.real; + offset += sizeof(this->mean); + union { + float real; + uint32_t base; + } u_std_dev; + u_std_dev.base = 0; + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_std_dev.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->std_dev = u_std_dev.real; + offset += sizeof(this->std_dev); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/AveragingResult"; }; + const char * getMD5(){ return "d5c7decf6df75ffb4367a05c1bcc7612"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciAction_h +#define _ROS_actionlib_tutorials_FibonacciAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "actionlib_tutorials/FibonacciActionGoal.h" +#include "actionlib_tutorials/FibonacciActionResult.h" +#include "actionlib_tutorials/FibonacciActionFeedback.h" + +namespace actionlib_tutorials +{ + + class FibonacciAction : public ros::Msg + { + public: + actionlib_tutorials::FibonacciActionGoal action_goal; + actionlib_tutorials::FibonacciActionResult action_result; + actionlib_tutorials::FibonacciActionFeedback action_feedback; + + FibonacciAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciAction"; }; + const char * getMD5(){ return "f59df5767bf7634684781c92598b2406"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionFeedback_h +#define _ROS_actionlib_tutorials_FibonacciActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/FibonacciFeedback.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib_tutorials::FibonacciFeedback feedback; + + FibonacciActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciActionFeedback"; }; + const char * getMD5(){ return "73b8497a9f629a31c0020900e4148f07"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionGoal_h +#define _ROS_actionlib_tutorials_FibonacciActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib_tutorials/FibonacciGoal.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + actionlib_tutorials::FibonacciGoal goal; + + FibonacciActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciActionGoal"; }; + const char * getMD5(){ return "006871c7fa1d0e3d5fe2226bf17b2a94"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionResult_h +#define _ROS_actionlib_tutorials_FibonacciActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/FibonacciResult.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + actionlib_tutorials::FibonacciResult result; + + FibonacciActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciActionResult"; }; + const char * getMD5(){ return "bee73a9fe29ae25e966e105f5553dd03"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciFeedback_h +#define _ROS_actionlib_tutorials_FibonacciFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciFeedback : public ros::Msg + { + public: + uint8_t sequence_length; + int32_t st_sequence; + int32_t * sequence; + + FibonacciFeedback(): + sequence_length(0), sequence(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = sequence_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_sequencei; + u_sequencei.real = this->sequence[i]; + *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t sequence_lengthT = *(inbuffer + offset++); + if(sequence_lengthT > sequence_length) + this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t)); + offset += 3; + sequence_length = sequence_lengthT; + for( uint8_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_sequence; + u_st_sequence.base = 0; + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_sequence = u_st_sequence.real; + offset += sizeof(this->st_sequence); + memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciFeedback"; }; + const char * getMD5(){ return "b81e37d2a31925a0e8ae261a8699cb79"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciGoal_h +#define _ROS_actionlib_tutorials_FibonacciGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciGoal : public ros::Msg + { + public: + int32_t order; + + FibonacciGoal(): + order(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_order; + u_order.real = this->order; + *(outbuffer + offset + 0) = (u_order.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_order.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_order.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_order.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->order); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_order; + u_order.base = 0; + u_order.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_order.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_order.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_order.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->order = u_order.real; + offset += sizeof(this->order); + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciGoal"; }; + const char * getMD5(){ return "6889063349a00b249bd1661df429d822"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/actionlib_tutorials/FibonacciResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciResult_h +#define _ROS_actionlib_tutorials_FibonacciResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciResult : public ros::Msg + { + public: + uint8_t sequence_length; + int32_t st_sequence; + int32_t * sequence; + + FibonacciResult(): + sequence_length(0), sequence(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = sequence_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_sequencei; + u_sequencei.real = this->sequence[i]; + *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t sequence_lengthT = *(inbuffer + offset++); + if(sequence_lengthT > sequence_length) + this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t)); + offset += 3; + sequence_length = sequence_lengthT; + for( uint8_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_sequence; + u_st_sequence.base = 0; + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_sequence = u_st_sequence.real; + offset += sizeof(this->st_sequence); + memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "actionlib_tutorials/FibonacciResult"; }; + const char * getMD5(){ return "b81e37d2a31925a0e8ae261a8699cb79"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/base_local_planner/Position2DInt.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,100 @@ +#ifndef _ROS_base_local_planner_Position2DInt_h +#define _ROS_base_local_planner_Position2DInt_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace base_local_planner +{ + + class Position2DInt : public ros::Msg + { + public: + int64_t x; + int64_t 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
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bond/Constants.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,44 @@ +#ifndef _ROS_bond_Constants_h +#define _ROS_bond_Constants_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace bond +{ + + class Constants : public ros::Msg + { + public: + enum { DEAD_PUBLISH_PERIOD = 0.05 }; + enum { DEFAULT_CONNECT_TIMEOUT = 10.0 }; + enum { DEFAULT_HEARTBEAT_TIMEOUT = 4.0 }; + enum { DEFAULT_DISCONNECT_TIMEOUT = 2.0 }; + enum { DEFAULT_HEARTBEAT_PERIOD = 1.0 }; + enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout }; + + Constants() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "bond/Constants"; }; + const char * getMD5(){ return "6fc594dc1d7bd7919077042712f8c8b0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bond/Status.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_bond_Status_h +#define _ROS_bond_Status_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace bond +{ + + class Status : public ros::Msg + { + public: + std_msgs::Header header; + const char* id; + const char* instance_id; + bool active; + float heartbeat_timeout; + float heartbeat_period; + + Status(): + header(), + id(""), + instance_id(""), + active(0), + heartbeat_timeout(0), + heartbeat_period(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + uint32_t length_instance_id = strlen(this->instance_id); + memcpy(outbuffer + offset, &length_instance_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->instance_id, length_instance_id); + offset += length_instance_id; + union { + bool real; + uint8_t base; + } u_active; + u_active.real = this->active; + *(outbuffer + offset + 0) = (u_active.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->active); + union { + float real; + uint32_t base; + } u_heartbeat_timeout; + u_heartbeat_timeout.real = this->heartbeat_timeout; + *(outbuffer + offset + 0) = (u_heartbeat_timeout.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_heartbeat_timeout.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_heartbeat_timeout.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_heartbeat_timeout.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->heartbeat_timeout); + union { + float real; + uint32_t base; + } u_heartbeat_period; + u_heartbeat_period.real = this->heartbeat_period; + *(outbuffer + offset + 0) = (u_heartbeat_period.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_heartbeat_period.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_heartbeat_period.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_heartbeat_period.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->heartbeat_period); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + uint32_t length_instance_id; + memcpy(&length_instance_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_instance_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_instance_id-1]=0; + this->instance_id = (char *)(inbuffer + offset-1); + offset += length_instance_id; + union { + bool real; + uint8_t base; + } u_active; + u_active.base = 0; + u_active.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->active = u_active.real; + offset += sizeof(this->active); + union { + float real; + uint32_t base; + } u_heartbeat_timeout; + u_heartbeat_timeout.base = 0; + u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_heartbeat_timeout.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->heartbeat_timeout = u_heartbeat_timeout.real; + offset += sizeof(this->heartbeat_timeout); + union { + float real; + uint32_t base; + } u_heartbeat_period; + u_heartbeat_period.base = 0; + u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_heartbeat_period.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->heartbeat_period = u_heartbeat_period.real; + offset += sizeof(this->heartbeat_period); + return offset; + } + + const char * getType(){ return "bond/Status"; }; + const char * getMD5(){ return "eacc84bf5d65b6777d4c50f463dfb9c8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryAction_h +#define _ROS_control_msgs_FollowJointTrajectoryAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/FollowJointTrajectoryActionGoal.h" +#include "control_msgs/FollowJointTrajectoryActionResult.h" +#include "control_msgs/FollowJointTrajectoryActionFeedback.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryAction : public ros::Msg + { + public: + control_msgs::FollowJointTrajectoryActionGoal action_goal; + control_msgs::FollowJointTrajectoryActionResult action_result; + control_msgs::FollowJointTrajectoryActionFeedback action_feedback; + + FollowJointTrajectoryAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryAction"; }; + const char * getMD5(){ return "a187484b9b42d27963c3e43098e345c9"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h +#define _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/FollowJointTrajectoryFeedback.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::FollowJointTrajectoryFeedback feedback; + + FollowJointTrajectoryActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryActionFeedback"; }; + const char * getMD5(){ return "d8920dc4eae9fc107e00999cce4be641"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryActionGoal_h +#define _ROS_control_msgs_FollowJointTrajectoryActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "control_msgs/FollowJointTrajectoryGoal.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + control_msgs::FollowJointTrajectoryGoal goal; + + FollowJointTrajectoryActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryActionGoal"; }; + const char * getMD5(){ return "cff5c1d533bf2f82dd0138d57f4304bb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryActionResult_h +#define _ROS_control_msgs_FollowJointTrajectoryActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/FollowJointTrajectoryResult.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::FollowJointTrajectoryResult result; + + FollowJointTrajectoryActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryActionResult"; }; + const char * getMD5(){ return "bce83d50f7bb28226801436caf0e2043"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryFeedback_h +#define _ROS_control_msgs_FollowJointTrajectoryFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "trajectory_msgs/JointTrajectoryPoint.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryFeedback : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + trajectory_msgs::JointTrajectoryPoint desired; + trajectory_msgs::JointTrajectoryPoint actual; + trajectory_msgs::JointTrajectoryPoint error; + + FollowJointTrajectoryFeedback(): + header(), + joint_names_length(0), joint_names(NULL), + desired(), + actual(), + error() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + offset += this->desired.serialize(outbuffer + offset); + offset += this->actual.serialize(outbuffer + offset); + offset += this->error.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + offset += this->desired.deserialize(inbuffer + offset); + offset += this->actual.deserialize(inbuffer + offset); + offset += this->error.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryFeedback"; }; + const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,107 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryGoal_h +#define _ROS_control_msgs_FollowJointTrajectoryGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "control_msgs/JointTolerance.h" +#include "ros/duration.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryGoal : public ros::Msg + { + public: + trajectory_msgs::JointTrajectory trajectory; + uint8_t path_tolerance_length; + control_msgs::JointTolerance st_path_tolerance; + control_msgs::JointTolerance * path_tolerance; + uint8_t goal_tolerance_length; + control_msgs::JointTolerance st_goal_tolerance; + control_msgs::JointTolerance * goal_tolerance; + ros::Duration goal_time_tolerance; + + FollowJointTrajectoryGoal(): + trajectory(), + path_tolerance_length(0), path_tolerance(NULL), + goal_tolerance_length(0), goal_tolerance(NULL), + goal_time_tolerance() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->trajectory.serialize(outbuffer + offset); + *(outbuffer + offset++) = path_tolerance_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < path_tolerance_length; i++){ + offset += this->path_tolerance[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = goal_tolerance_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < goal_tolerance_length; i++){ + offset += this->goal_tolerance[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->goal_time_tolerance.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->goal_time_tolerance.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->goal_time_tolerance.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->goal_time_tolerance.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->goal_time_tolerance.sec); + *(outbuffer + offset + 0) = (this->goal_time_tolerance.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->goal_time_tolerance.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->goal_time_tolerance.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->goal_time_tolerance.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->goal_time_tolerance.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->trajectory.deserialize(inbuffer + offset); + uint8_t path_tolerance_lengthT = *(inbuffer + offset++); + if(path_tolerance_lengthT > path_tolerance_length) + this->path_tolerance = (control_msgs::JointTolerance*)realloc(this->path_tolerance, path_tolerance_lengthT * sizeof(control_msgs::JointTolerance)); + offset += 3; + path_tolerance_length = path_tolerance_lengthT; + for( uint8_t i = 0; i < path_tolerance_length; i++){ + offset += this->st_path_tolerance.deserialize(inbuffer + offset); + memcpy( &(this->path_tolerance[i]), &(this->st_path_tolerance), sizeof(control_msgs::JointTolerance)); + } + uint8_t goal_tolerance_lengthT = *(inbuffer + offset++); + if(goal_tolerance_lengthT > goal_tolerance_length) + this->goal_tolerance = (control_msgs::JointTolerance*)realloc(this->goal_tolerance, goal_tolerance_lengthT * sizeof(control_msgs::JointTolerance)); + offset += 3; + goal_tolerance_length = goal_tolerance_lengthT; + for( uint8_t i = 0; i < goal_tolerance_length; i++){ + offset += this->st_goal_tolerance.deserialize(inbuffer + offset); + memcpy( &(this->goal_tolerance[i]), &(this->st_goal_tolerance), sizeof(control_msgs::JointTolerance)); + } + this->goal_time_tolerance.sec = ((uint32_t) (*(inbuffer + offset))); + this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->goal_time_tolerance.sec); + this->goal_time_tolerance.nsec = ((uint32_t) (*(inbuffer + offset))); + this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->goal_time_tolerance.nsec); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryGoal"; }; + const char * getMD5(){ return "69636787b6ecbde4d61d711979bc7ecb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/FollowJointTrajectoryResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_control_msgs_FollowJointTrajectoryResult_h +#define _ROS_control_msgs_FollowJointTrajectoryResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class FollowJointTrajectoryResult : public ros::Msg + { + public: + int32_t error_code; + 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) + { + } + + 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); + 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); + return offset; + } + + const char * getType(){ return "control_msgs/FollowJointTrajectoryResult"; }; + const char * getMD5(){ return "6243274b5d629dc838814109754410d5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommand.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,46 @@ +#ifndef _ROS_control_msgs_GripperCommand_h +#define _ROS_control_msgs_GripperCommand_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class GripperCommand : public ros::Msg + { + public: + float position; + float max_effort; + + GripperCommand(): + position(0), + max_effort(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->max_effort); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_effort)); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommand"; }; + const char * getMD5(){ return "680acaff79486f017132a7f198d40f08"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_GripperCommandAction_h +#define _ROS_control_msgs_GripperCommandAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/GripperCommandActionGoal.h" +#include "control_msgs/GripperCommandActionResult.h" +#include "control_msgs/GripperCommandActionFeedback.h" + +namespace control_msgs +{ + + class GripperCommandAction : public ros::Msg + { + public: + control_msgs::GripperCommandActionGoal action_goal; + control_msgs::GripperCommandActionResult action_result; + control_msgs::GripperCommandActionFeedback action_feedback; + + GripperCommandAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommandAction"; }; + const char * getMD5(){ return "950b2a6ebe831f5d4f4ceaba3d8be01e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_GripperCommandActionFeedback_h +#define _ROS_control_msgs_GripperCommandActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/GripperCommandFeedback.h" + +namespace control_msgs +{ + + class GripperCommandActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::GripperCommandFeedback feedback; + + GripperCommandActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommandActionFeedback"; }; + const char * getMD5(){ return "653dff30c045f5e6ff3feb3409f4558d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_GripperCommandActionGoal_h +#define _ROS_control_msgs_GripperCommandActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "control_msgs/GripperCommandGoal.h" + +namespace control_msgs +{ + + class GripperCommandActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + control_msgs::GripperCommandGoal goal; + + GripperCommandActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommandActionGoal"; }; + const char * getMD5(){ return "aa581f648a35ed681db2ec0bf7a82bea"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_GripperCommandActionResult_h +#define _ROS_control_msgs_GripperCommandActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/GripperCommandResult.h" + +namespace control_msgs +{ + + class GripperCommandActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::GripperCommandResult result; + + GripperCommandActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommandActionResult"; }; + const char * getMD5(){ return "143702cb2df0f163c5283cedc5efc6b6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_control_msgs_GripperCommandFeedback_h +#define _ROS_control_msgs_GripperCommandFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class GripperCommandFeedback : public ros::Msg + { + public: + float position; + float effort; + bool stalled; + bool reached_goal; + + GripperCommandFeedback(): + position(0), + effort(0), + stalled(0), + reached_goal(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, 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; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(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
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_control_msgs_GripperCommandGoal_h +#define _ROS_control_msgs_GripperCommandGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/GripperCommand.h" + +namespace control_msgs +{ + + class GripperCommandGoal : public ros::Msg + { + public: + control_msgs::GripperCommand command; + + GripperCommandGoal(): + command() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->command.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->command.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/GripperCommandGoal"; }; + const char * getMD5(){ return "86fd82f4ddc48a4cb6856cfa69217e43"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/GripperCommandResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_control_msgs_GripperCommandResult_h +#define _ROS_control_msgs_GripperCommandResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class GripperCommandResult : public ros::Msg + { + public: + float position; + float effort; + bool stalled; + bool reached_goal; + + GripperCommandResult(): + position(0), + effort(0), + stalled(0), + reached_goal(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, 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; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(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
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointControllerState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,83 @@ +#ifndef _ROS_control_msgs_JointControllerState_h +#define _ROS_control_msgs_JointControllerState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace control_msgs +{ + + class JointControllerState : public ros::Msg + { + public: + std_msgs::Header header; + float set_point; + float process_value; + float process_value_dot; + float error; + float time_step; + float command; + float p; + float i; + float d; + float i_clamp; + + JointControllerState(): + header(), + set_point(0), + process_value(0), + process_value_dot(0), + error(0), + time_step(0), + command(0), + p(0), + i(0), + d(0), + i_clamp(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->set_point); + offset += serializeAvrFloat64(outbuffer + offset, this->process_value); + offset += serializeAvrFloat64(outbuffer + offset, this->process_value_dot); + offset += serializeAvrFloat64(outbuffer + offset, this->error); + offset += serializeAvrFloat64(outbuffer + offset, this->time_step); + offset += serializeAvrFloat64(outbuffer + offset, this->command); + offset += serializeAvrFloat64(outbuffer + offset, this->p); + offset += serializeAvrFloat64(outbuffer + offset, this->i); + offset += serializeAvrFloat64(outbuffer + offset, this->d); + offset += serializeAvrFloat64(outbuffer + offset, this->i_clamp); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->set_point)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->process_value)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->process_value_dot)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->error)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->time_step)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->command)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->p)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->i)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->d)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->i_clamp)); + return offset; + } + + const char * getType(){ return "control_msgs/JointControllerState"; }; + const char * getMD5(){ return "c0d034a7bf20aeb1c37f3eccb7992b69"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTolerance.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,66 @@ +#ifndef _ROS_control_msgs_JointTolerance_h +#define _ROS_control_msgs_JointTolerance_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class JointTolerance : public ros::Msg + { + public: + const char* name; + float position; + float velocity; + float acceleration; + + JointTolerance(): + name(""), + position(0), + velocity(0), + acceleration(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->velocity); + offset += serializeAvrFloat64(outbuffer + offset, this->acceleration); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->velocity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->acceleration)); + return offset; + } + + const char * getType(){ return "control_msgs/JointTolerance"; }; + const char * getMD5(){ return "f544fe9c16cf04547e135dd6063ff5be"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_JointTrajectoryAction_h +#define _ROS_control_msgs_JointTrajectoryAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/JointTrajectoryActionGoal.h" +#include "control_msgs/JointTrajectoryActionResult.h" +#include "control_msgs/JointTrajectoryActionFeedback.h" + +namespace control_msgs +{ + + class JointTrajectoryAction : public ros::Msg + { + public: + control_msgs::JointTrajectoryActionGoal action_goal; + control_msgs::JointTrajectoryActionResult action_result; + control_msgs::JointTrajectoryActionFeedback action_feedback; + + JointTrajectoryAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryAction"; }; + const char * getMD5(){ return "a04ba3ee8f6a2d0985a6aeaf23d9d7ad"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_JointTrajectoryActionFeedback_h +#define _ROS_control_msgs_JointTrajectoryActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/JointTrajectoryFeedback.h" + +namespace control_msgs +{ + + class JointTrajectoryActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::JointTrajectoryFeedback feedback; + + JointTrajectoryActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_JointTrajectoryActionGoal_h +#define _ROS_control_msgs_JointTrajectoryActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "control_msgs/JointTrajectoryGoal.h" + +namespace control_msgs +{ + + class JointTrajectoryActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + control_msgs::JointTrajectoryGoal goal; + + JointTrajectoryActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryActionGoal"; }; + const char * getMD5(){ return "a99e83ef6185f9fdd7693efe99623a86"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_JointTrajectoryActionResult_h +#define _ROS_control_msgs_JointTrajectoryActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/JointTrajectoryResult.h" + +namespace control_msgs +{ + + class JointTrajectoryActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::JointTrajectoryResult result; + + JointTrajectoryActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryActionResult"; }; + const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryControllerState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_control_msgs_JointTrajectoryControllerState_h +#define _ROS_control_msgs_JointTrajectoryControllerState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "trajectory_msgs/JointTrajectoryPoint.h" + +namespace control_msgs +{ + + class JointTrajectoryControllerState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + trajectory_msgs::JointTrajectoryPoint desired; + trajectory_msgs::JointTrajectoryPoint actual; + trajectory_msgs::JointTrajectoryPoint error; + + JointTrajectoryControllerState(): + header(), + joint_names_length(0), joint_names(NULL), + desired(), + actual(), + error() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + offset += this->desired.serialize(outbuffer + offset); + offset += this->actual.serialize(outbuffer + offset); + offset += this->error.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + offset += this->desired.deserialize(inbuffer + offset); + offset += this->actual.deserialize(inbuffer + offset); + offset += this->error.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryControllerState"; }; + const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_control_msgs_JointTrajectoryFeedback_h +#define _ROS_control_msgs_JointTrajectoryFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class JointTrajectoryFeedback : public ros::Msg + { + public: + + JointTrajectoryFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_control_msgs_JointTrajectoryGoal_h +#define _ROS_control_msgs_JointTrajectoryGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" + +namespace control_msgs +{ + + class JointTrajectoryGoal : public ros::Msg + { + public: + trajectory_msgs::JointTrajectory trajectory; + + JointTrajectoryGoal(): + trajectory() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->trajectory.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->trajectory.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryGoal"; }; + const char * getMD5(){ return "2a0eff76c870e8595636c2a562ca298e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/JointTrajectoryResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_control_msgs_JointTrajectoryResult_h +#define _ROS_control_msgs_JointTrajectoryResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class JointTrajectoryResult : public ros::Msg + { + public: + + JointTrajectoryResult() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "control_msgs/JointTrajectoryResult"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_PointHeadAction_h +#define _ROS_control_msgs_PointHeadAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/PointHeadActionGoal.h" +#include "control_msgs/PointHeadActionResult.h" +#include "control_msgs/PointHeadActionFeedback.h" + +namespace control_msgs +{ + + class PointHeadAction : public ros::Msg + { + public: + control_msgs::PointHeadActionGoal action_goal; + control_msgs::PointHeadActionResult action_result; + control_msgs::PointHeadActionFeedback action_feedback; + + PointHeadAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadAction"; }; + const char * getMD5(){ return "7252920f1243de1b741f14f214125371"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_PointHeadActionFeedback_h +#define _ROS_control_msgs_PointHeadActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/PointHeadFeedback.h" + +namespace control_msgs +{ + + class PointHeadActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::PointHeadFeedback feedback; + + PointHeadActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadActionFeedback"; }; + const char * getMD5(){ return "33c9244957176bbba97dd641119e8460"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_PointHeadActionGoal_h +#define _ROS_control_msgs_PointHeadActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "control_msgs/PointHeadGoal.h" + +namespace control_msgs +{ + + class PointHeadActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + control_msgs::PointHeadGoal goal; + + PointHeadActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadActionGoal"; }; + const char * getMD5(){ return "b53a8323d0ba7b310ba17a2d3a82a6b8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_PointHeadActionResult_h +#define _ROS_control_msgs_PointHeadActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/PointHeadResult.h" + +namespace control_msgs +{ + + class PointHeadActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::PointHeadResult result; + + PointHeadActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadActionResult"; }; + const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_control_msgs_PointHeadFeedback_h +#define _ROS_control_msgs_PointHeadFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class PointHeadFeedback : public ros::Msg + { + public: + float pointing_angle_error; + + PointHeadFeedback(): + pointing_angle_error(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->pointing_angle_error); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->pointing_angle_error)); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadFeedback"; }; + const char * getMD5(){ return "cce80d27fd763682da8805a73316cab4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,91 @@ +#ifndef _ROS_control_msgs_PointHeadGoal_h +#define _ROS_control_msgs_PointHeadGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PointStamped.h" +#include "geometry_msgs/Vector3.h" +#include "ros/duration.h" + +namespace control_msgs +{ + + class PointHeadGoal : public ros::Msg + { + public: + geometry_msgs::PointStamped target; + geometry_msgs::Vector3 pointing_axis; + const char* pointing_frame; + ros::Duration min_duration; + float max_velocity; + + PointHeadGoal(): + target(), + pointing_axis(), + pointing_frame(""), + min_duration(), + max_velocity(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->target.serialize(outbuffer + offset); + offset += this->pointing_axis.serialize(outbuffer + offset); + uint32_t length_pointing_frame = strlen(this->pointing_frame); + memcpy(outbuffer + offset, &length_pointing_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->pointing_frame, length_pointing_frame); + offset += length_pointing_frame; + *(outbuffer + offset + 0) = (this->min_duration.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->min_duration.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->min_duration.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->min_duration.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_duration.sec); + *(outbuffer + offset + 0) = (this->min_duration.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->min_duration.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->min_duration.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->min_duration.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_duration.nsec); + offset += serializeAvrFloat64(outbuffer + offset, this->max_velocity); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->target.deserialize(inbuffer + offset); + offset += this->pointing_axis.deserialize(inbuffer + offset); + uint32_t length_pointing_frame; + memcpy(&length_pointing_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_pointing_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_pointing_frame-1]=0; + this->pointing_frame = (char *)(inbuffer + offset-1); + offset += length_pointing_frame; + this->min_duration.sec = ((uint32_t) (*(inbuffer + offset))); + this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->min_duration.sec); + this->min_duration.nsec = ((uint32_t) (*(inbuffer + offset))); + this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->min_duration.nsec); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_velocity)); + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadGoal"; }; + const char * getMD5(){ return "8b92b1cd5e06c8a94c917dc3209a4c1d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/PointHeadResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_control_msgs_PointHeadResult_h +#define _ROS_control_msgs_PointHeadResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class PointHeadResult : public ros::Msg + { + public: + + PointHeadResult() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "control_msgs/PointHeadResult"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/QueryCalibrationState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,88 @@ +#ifndef _ROS_SERVICE_QueryCalibrationState_h +#define _ROS_SERVICE_QueryCalibrationState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + +static const char QUERYCALIBRATIONSTATE[] = "control_msgs/QueryCalibrationState"; + + class QueryCalibrationStateRequest : public ros::Msg + { + public: + + QueryCalibrationStateRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return QUERYCALIBRATIONSTATE; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class QueryCalibrationStateResponse : public ros::Msg + { + public: + bool is_calibrated; + + QueryCalibrationStateResponse(): + is_calibrated(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_is_calibrated; + u_is_calibrated.real = this->is_calibrated; + *(outbuffer + offset + 0) = (u_is_calibrated.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_calibrated); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_is_calibrated; + u_is_calibrated.base = 0; + u_is_calibrated.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_calibrated = u_is_calibrated.real; + offset += sizeof(this->is_calibrated); + return offset; + } + + const char * getType(){ return QUERYCALIBRATIONSTATE; }; + const char * getMD5(){ return "28af3beedcb84986b8e470dc5470507d"; }; + + }; + + class QueryCalibrationState { + public: + typedef QueryCalibrationStateRequest Request; + typedef QueryCalibrationStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/QueryTrajectoryState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,186 @@ +#ifndef _ROS_SERVICE_QueryTrajectoryState_h +#define _ROS_SERVICE_QueryTrajectoryState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace control_msgs +{ + +static const char QUERYTRAJECTORYSTATE[] = "control_msgs/QueryTrajectoryState"; + + class QueryTrajectoryStateRequest : public ros::Msg + { + public: + ros::Time time; + + QueryTrajectoryStateRequest(): + time() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time.sec); + *(outbuffer + offset + 0) = (this->time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->time.sec = ((uint32_t) (*(inbuffer + offset))); + this->time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time.sec); + this->time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time.nsec); + return offset; + } + + const char * getType(){ return QUERYTRAJECTORYSTATE; }; + const char * getMD5(){ return "556a4fb76023a469987922359d08a844"; }; + + }; + + class QueryTrajectoryStateResponse : public ros::Msg + { + public: + uint8_t name_length; + char* st_name; + char* * name; + uint8_t position_length; + float st_position; + float * position; + uint8_t velocity_length; + float st_velocity; + float * velocity; + uint8_t acceleration_length; + float st_acceleration; + float * acceleration; + + QueryTrajectoryStateResponse(): + name_length(0), name(NULL), + position_length(0), position(NULL), + velocity_length(0), velocity(NULL), + acceleration_length(0), acceleration(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = position_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < position_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->position[i]); + } + *(outbuffer + offset++) = velocity_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < velocity_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->velocity[i]); + } + *(outbuffer + offset++) = acceleration_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < acceleration_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->acceleration[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t position_lengthT = *(inbuffer + offset++); + if(position_lengthT > position_length) + this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); + offset += 3; + position_length = position_lengthT; + for( uint8_t i = 0; i < position_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_position)); + memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); + } + uint8_t velocity_lengthT = *(inbuffer + offset++); + if(velocity_lengthT > velocity_length) + this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float)); + offset += 3; + velocity_length = velocity_lengthT; + for( uint8_t i = 0; i < velocity_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_velocity)); + memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float)); + } + uint8_t acceleration_lengthT = *(inbuffer + offset++); + if(acceleration_lengthT > acceleration_length) + this->acceleration = (float*)realloc(this->acceleration, acceleration_lengthT * sizeof(float)); + offset += 3; + acceleration_length = acceleration_lengthT; + for( uint8_t i = 0; i < acceleration_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_acceleration)); + memcpy( &(this->acceleration[i]), &(this->st_acceleration), sizeof(float)); + } + return offset; + } + + const char * getType(){ return QUERYTRAJECTORYSTATE; }; + const char * getMD5(){ return "1f1a6554ad060f44d013e71868403c1a"; }; + + }; + + class QueryTrajectoryState { + public: + typedef QueryTrajectoryStateRequest Request; + typedef QueryTrajectoryStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_SingleJointPositionAction_h +#define _ROS_control_msgs_SingleJointPositionAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "control_msgs/SingleJointPositionActionGoal.h" +#include "control_msgs/SingleJointPositionActionResult.h" +#include "control_msgs/SingleJointPositionActionFeedback.h" + +namespace control_msgs +{ + + class SingleJointPositionAction : public ros::Msg + { + public: + control_msgs::SingleJointPositionActionGoal action_goal; + control_msgs::SingleJointPositionActionResult action_result; + control_msgs::SingleJointPositionActionFeedback action_feedback; + + SingleJointPositionAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionAction"; }; + const char * getMD5(){ return "c4a786b7d53e5d0983decf967a5a779e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_SingleJointPositionActionFeedback_h +#define _ROS_control_msgs_SingleJointPositionActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/SingleJointPositionFeedback.h" + +namespace control_msgs +{ + + class SingleJointPositionActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::SingleJointPositionFeedback feedback; + + SingleJointPositionActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionActionFeedback"; }; + const char * getMD5(){ return "3503b7cf8972f90d245850a5d8796cfa"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_SingleJointPositionActionGoal_h +#define _ROS_control_msgs_SingleJointPositionActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "control_msgs/SingleJointPositionGoal.h" + +namespace control_msgs +{ + + class SingleJointPositionActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + control_msgs::SingleJointPositionGoal goal; + + SingleJointPositionActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionActionGoal"; }; + const char * getMD5(){ return "4b0d3d091471663e17749c1d0db90f61"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_control_msgs_SingleJointPositionActionResult_h +#define _ROS_control_msgs_SingleJointPositionActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "control_msgs/SingleJointPositionResult.h" + +namespace control_msgs +{ + + class SingleJointPositionActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + control_msgs::SingleJointPositionResult result; + + SingleJointPositionActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionActionResult"; }; + const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,55 @@ +#ifndef _ROS_control_msgs_SingleJointPositionFeedback_h +#define _ROS_control_msgs_SingleJointPositionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace control_msgs +{ + + class SingleJointPositionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + float position; + float velocity; + float 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); + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->velocity); + offset += serializeAvrFloat64(outbuffer + offset, this->error); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->velocity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->error)); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionFeedback"; }; + const char * getMD5(){ return "8cee65610a3d08e0a1bded82f146f1fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_control_msgs_SingleJointPositionGoal_h +#define _ROS_control_msgs_SingleJointPositionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace control_msgs +{ + + class SingleJointPositionGoal : public ros::Msg + { + public: + float position; + ros::Duration min_duration; + float max_velocity; + + SingleJointPositionGoal(): + position(0), + min_duration(), + max_velocity(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, 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); + offset += serializeAvrFloat64(outbuffer + offset, this->max_velocity); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(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); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_velocity)); + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionGoal"; }; + const char * getMD5(){ return "fbaaa562a23a013fd5053e5f72cbb35c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_msgs/SingleJointPositionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_control_msgs_SingleJointPositionResult_h +#define _ROS_control_msgs_SingleJointPositionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_msgs +{ + + class SingleJointPositionResult : public ros::Msg + { + public: + + SingleJointPositionResult() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "control_msgs/SingleJointPositionResult"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/control_toolbox/SetPidGains.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_SetPidGains_h +#define _ROS_SERVICE_SetPidGains_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace control_toolbox +{ + +static const char SETPIDGAINS[] = "control_toolbox/SetPidGains"; + + class SetPidGainsRequest : public ros::Msg + { + public: + float p; + float i; + float d; + float i_clamp; + + SetPidGainsRequest(): + p(0), + i(0), + d(0), + i_clamp(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->p); + offset += serializeAvrFloat64(outbuffer + offset, this->i); + offset += serializeAvrFloat64(outbuffer + offset, this->d); + offset += serializeAvrFloat64(outbuffer + offset, this->i_clamp); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->p)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->i)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->d)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->i_clamp)); + return offset; + } + + const char * getType(){ return SETPIDGAINS; }; + const char * getMD5(){ return "b06494a6fc3d5b972ded4e2a9a71535a"; }; + + }; + + 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 +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ControllerState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,134 @@ +#ifndef _ROS_controller_manager_msgs_ControllerState_h +#define _ROS_controller_manager_msgs_ControllerState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + + class ControllerState : public ros::Msg + { + public: + const char* name; + const char* state; + const char* type; + const char* hardware_interface; + uint8_t resources_length; + char* st_resources; + char* * resources; + + ControllerState(): + name(""), + state(""), + type(""), + hardware_interface(""), + resources_length(0), resources(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_state = strlen(this->state); + memcpy(outbuffer + offset, &length_state, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->state, length_state); + offset += length_state; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + uint32_t length_hardware_interface = strlen(this->hardware_interface); + memcpy(outbuffer + offset, &length_hardware_interface, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->hardware_interface, length_hardware_interface); + offset += length_hardware_interface; + *(outbuffer + offset++) = resources_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < resources_length; i++){ + uint32_t length_resourcesi = strlen(this->resources[i]); + memcpy(outbuffer + offset, &length_resourcesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->resources[i], length_resourcesi); + offset += length_resourcesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_state; + memcpy(&length_state, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_state; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_state-1]=0; + this->state = (char *)(inbuffer + offset-1); + offset += length_state; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + uint32_t length_hardware_interface; + memcpy(&length_hardware_interface, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_hardware_interface; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_hardware_interface-1]=0; + this->hardware_interface = (char *)(inbuffer + offset-1); + offset += length_hardware_interface; + uint8_t resources_lengthT = *(inbuffer + offset++); + if(resources_lengthT > resources_length) + this->resources = (char**)realloc(this->resources, resources_lengthT * sizeof(char*)); + offset += 3; + resources_length = resources_lengthT; + for( uint8_t i = 0; i < resources_length; i++){ + uint32_t length_st_resources; + memcpy(&length_st_resources, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_resources; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_resources-1]=0; + this->st_resources = (char *)(inbuffer + offset-1); + offset += length_st_resources; + memcpy( &(this->resources[i]), &(this->st_resources), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "controller_manager_msgs/ControllerState"; }; + const char * getMD5(){ return "cac963cc68f4f5836765c108de0fc446"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ControllerStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,222 @@ +#ifndef _ROS_controller_manager_msgs_ControllerStatistics_h +#define _ROS_controller_manager_msgs_ControllerStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "ros/duration.h" + +namespace controller_manager_msgs +{ + + class ControllerStatistics : public ros::Msg + { + public: + const char* name; + const char* type; + ros::Time timestamp; + bool running; + ros::Duration max_time; + ros::Duration mean_time; + ros::Duration variance_time; + int32_t num_control_loop_overruns; + ros::Time time_last_control_loop_overrun; + + ControllerStatistics(): + name(""), + type(""), + timestamp(), + running(0), + max_time(), + mean_time(), + variance_time(), + num_control_loop_overruns(0), + time_last_control_loop_overrun() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + *(outbuffer + offset + 0) = (this->timestamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.sec); + *(outbuffer + offset + 0) = (this->timestamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.nsec); + union { + bool real; + uint8_t base; + } u_running; + u_running.real = this->running; + *(outbuffer + offset + 0) = (u_running.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->running); + *(outbuffer + offset + 0) = (this->max_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->max_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->max_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->max_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_time.sec); + *(outbuffer + offset + 0) = (this->max_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->max_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->max_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->max_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_time.nsec); + *(outbuffer + offset + 0) = (this->mean_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->mean_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->mean_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->mean_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean_time.sec); + *(outbuffer + offset + 0) = (this->mean_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->mean_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->mean_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->mean_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean_time.nsec); + *(outbuffer + offset + 0) = (this->variance_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->variance_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->variance_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->variance_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->variance_time.sec); + *(outbuffer + offset + 0) = (this->variance_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->variance_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->variance_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->variance_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->variance_time.nsec); + union { + int32_t real; + uint32_t base; + } u_num_control_loop_overruns; + u_num_control_loop_overruns.real = this->num_control_loop_overruns; + *(outbuffer + offset + 0) = (u_num_control_loop_overruns.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_num_control_loop_overruns.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_num_control_loop_overruns.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_num_control_loop_overruns.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->num_control_loop_overruns); + *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_last_control_loop_overrun.sec); + *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_last_control_loop_overrun.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + this->timestamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.sec); + this->timestamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.nsec); + union { + bool real; + uint8_t base; + } u_running; + u_running.base = 0; + u_running.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->running = u_running.real; + offset += sizeof(this->running); + this->max_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->max_time.sec); + this->max_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->max_time.nsec); + this->mean_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->mean_time.sec); + this->mean_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->mean_time.nsec); + this->variance_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->variance_time.sec); + this->variance_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->variance_time.nsec); + union { + int32_t real; + uint32_t base; + } u_num_control_loop_overruns; + u_num_control_loop_overruns.base = 0; + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->num_control_loop_overruns = u_num_control_loop_overruns.real; + offset += sizeof(this->num_control_loop_overruns); + this->time_last_control_loop_overrun.sec = ((uint32_t) (*(inbuffer + offset))); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_last_control_loop_overrun.sec); + this->time_last_control_loop_overrun.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_last_control_loop_overrun.nsec); + return offset; + } + + const char * getType(){ return "controller_manager_msgs/ControllerStatistics"; }; + const char * getMD5(){ return "697780c372c8d8597a1436d0e2ad3ba8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ControllersStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_controller_manager_msgs_ControllersStatistics_h +#define _ROS_controller_manager_msgs_ControllersStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "controller_manager_msgs/ControllerStatistics.h" + +namespace controller_manager_msgs +{ + + class ControllersStatistics : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t controller_length; + controller_manager_msgs::ControllerStatistics st_controller; + controller_manager_msgs::ControllerStatistics * controller; + + ControllersStatistics(): + header(), + controller_length(0), controller(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = controller_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < controller_length; i++){ + offset += this->controller[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t controller_lengthT = *(inbuffer + offset++); + if(controller_lengthT > controller_length) + this->controller = (controller_manager_msgs::ControllerStatistics*)realloc(this->controller, controller_lengthT * sizeof(controller_manager_msgs::ControllerStatistics)); + offset += 3; + controller_length = controller_lengthT; + for( uint8_t i = 0; i < controller_length; i++){ + offset += this->st_controller.deserialize(inbuffer + offset); + memcpy( &(this->controller[i]), &(this->st_controller), sizeof(controller_manager_msgs::ControllerStatistics)); + } + return offset; + } + + const char * getType(){ return "controller_manager_msgs/ControllersStatistics"; }; + const char * getMD5(){ return "a154c347736773e3700d1719105df29d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ListControllerTypes.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,135 @@ +#ifndef _ROS_SERVICE_ListControllerTypes_h +#define _ROS_SERVICE_ListControllerTypes_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char LISTCONTROLLERTYPES[] = "controller_manager_msgs/ListControllerTypes"; + + class ListControllerTypesRequest : public ros::Msg + { + public: + + ListControllerTypesRequest() + { + } + + 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 LISTCONTROLLERTYPES; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class ListControllerTypesResponse : public ros::Msg + { + public: + uint8_t types_length; + char* st_types; + char* * types; + uint8_t base_classes_length; + char* st_base_classes; + char* * base_classes; + + ListControllerTypesResponse(): + types_length(0), types(NULL), + base_classes_length(0), base_classes(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = types_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < types_length; i++){ + uint32_t length_typesi = strlen(this->types[i]); + memcpy(outbuffer + offset, &length_typesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->types[i], length_typesi); + offset += length_typesi; + } + *(outbuffer + offset++) = base_classes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < base_classes_length; i++){ + uint32_t length_base_classesi = strlen(this->base_classes[i]); + memcpy(outbuffer + offset, &length_base_classesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->base_classes[i], length_base_classesi); + offset += length_base_classesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t types_lengthT = *(inbuffer + offset++); + if(types_lengthT > types_length) + this->types = (char**)realloc(this->types, types_lengthT * sizeof(char*)); + offset += 3; + types_length = types_lengthT; + for( uint8_t i = 0; i < types_length; i++){ + uint32_t length_st_types; + memcpy(&length_st_types, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_types; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_types-1]=0; + this->st_types = (char *)(inbuffer + offset-1); + offset += length_st_types; + memcpy( &(this->types[i]), &(this->st_types), sizeof(char*)); + } + uint8_t base_classes_lengthT = *(inbuffer + offset++); + if(base_classes_lengthT > base_classes_length) + this->base_classes = (char**)realloc(this->base_classes, base_classes_lengthT * sizeof(char*)); + offset += 3; + base_classes_length = base_classes_lengthT; + for( uint8_t i = 0; i < base_classes_length; i++){ + uint32_t length_st_base_classes; + memcpy(&length_st_base_classes, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_base_classes; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_base_classes-1]=0; + this->st_base_classes = (char *)(inbuffer + offset-1); + offset += length_st_base_classes; + memcpy( &(this->base_classes[i]), &(this->st_base_classes), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return LISTCONTROLLERTYPES; }; + const char * getMD5(){ return "c1d4cd11aefa9f97ba4aeb5b33987f4e"; }; + + }; + + class ListControllerTypes { + public: + typedef ListControllerTypesRequest Request; + typedef ListControllerTypesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ListControllers.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_ListControllers_h +#define _ROS_SERVICE_ListControllers_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "controller_manager_msgs/ControllerState.h" + +namespace controller_manager_msgs +{ + +static const char LISTCONTROLLERS[] = "controller_manager_msgs/ListControllers"; + + class ListControllersRequest : public ros::Msg + { + public: + + ListControllersRequest() + { + } + + 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 LISTCONTROLLERS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class ListControllersResponse : public ros::Msg + { + public: + uint8_t controller_length; + controller_manager_msgs::ControllerState st_controller; + controller_manager_msgs::ControllerState * controller; + + ListControllersResponse(): + controller_length(0), controller(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = controller_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < controller_length; i++){ + offset += this->controller[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t controller_lengthT = *(inbuffer + offset++); + if(controller_lengthT > controller_length) + this->controller = (controller_manager_msgs::ControllerState*)realloc(this->controller, controller_lengthT * sizeof(controller_manager_msgs::ControllerState)); + offset += 3; + controller_length = controller_lengthT; + for( uint8_t i = 0; i < controller_length; i++){ + offset += this->st_controller.deserialize(inbuffer + offset); + memcpy( &(this->controller[i]), &(this->st_controller), sizeof(controller_manager_msgs::ControllerState)); + } + return offset; + } + + const char * getType(){ return LISTCONTROLLERS; }; + const char * getMD5(){ return "12c85fca1984c8ec86264f3d00b938f2"; }; + + }; + + class ListControllers { + public: + typedef ListControllersRequest Request; + typedef ListControllersResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/LoadController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_LoadController_h +#define _ROS_SERVICE_LoadController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char LOADCONTROLLER[] = "controller_manager_msgs/LoadController"; + + class LoadControllerRequest : public ros::Msg + { + public: + const char* name; + + LoadControllerRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class LoadControllerResponse : public ros::Msg + { + public: + bool ok; + + LoadControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class LoadController { + public: + typedef LoadControllerRequest Request; + typedef LoadControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/ReloadControllerLibraries.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,105 @@ +#ifndef _ROS_SERVICE_ReloadControllerLibraries_h +#define _ROS_SERVICE_ReloadControllerLibraries_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char RELOADCONTROLLERLIBRARIES[] = "controller_manager_msgs/ReloadControllerLibraries"; + + class ReloadControllerLibrariesRequest : public ros::Msg + { + public: + bool force_kill; + + ReloadControllerLibrariesRequest(): + force_kill(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_force_kill; + u_force_kill.real = this->force_kill; + *(outbuffer + offset + 0) = (u_force_kill.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->force_kill); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_force_kill; + u_force_kill.base = 0; + u_force_kill.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->force_kill = u_force_kill.real; + offset += sizeof(this->force_kill); + return offset; + } + + const char * getType(){ return RELOADCONTROLLERLIBRARIES; }; + const char * getMD5(){ return "18442b59be9479097f11c543bddbac62"; }; + + }; + + class ReloadControllerLibrariesResponse : public ros::Msg + { + public: + bool ok; + + ReloadControllerLibrariesResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return RELOADCONTROLLERLIBRARIES; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class ReloadControllerLibraries { + public: + typedef ReloadControllerLibrariesRequest Request; + typedef ReloadControllerLibrariesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/SwitchController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,177 @@ +#ifndef _ROS_SERVICE_SwitchController_h +#define _ROS_SERVICE_SwitchController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char SWITCHCONTROLLER[] = "controller_manager_msgs/SwitchController"; + + class SwitchControllerRequest : public ros::Msg + { + public: + uint8_t start_controllers_length; + char* st_start_controllers; + char* * start_controllers; + uint8_t stop_controllers_length; + char* st_stop_controllers; + char* * stop_controllers; + int32_t strictness; + enum { BEST_EFFORT = 1 }; + enum { STRICT = 2 }; + + SwitchControllerRequest(): + start_controllers_length(0), start_controllers(NULL), + stop_controllers_length(0), stop_controllers(NULL), + strictness(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = start_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_start_controllersi = strlen(this->start_controllers[i]); + memcpy(outbuffer + offset, &length_start_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->start_controllers[i], length_start_controllersi); + offset += length_start_controllersi; + } + *(outbuffer + offset++) = stop_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_stop_controllersi = strlen(this->stop_controllers[i]); + memcpy(outbuffer + offset, &length_stop_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->stop_controllers[i], length_stop_controllersi); + offset += length_stop_controllersi; + } + union { + int32_t real; + uint32_t base; + } u_strictness; + u_strictness.real = this->strictness; + *(outbuffer + offset + 0) = (u_strictness.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_strictness.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_strictness.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_strictness.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->strictness); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t start_controllers_lengthT = *(inbuffer + offset++); + if(start_controllers_lengthT > start_controllers_length) + this->start_controllers = (char**)realloc(this->start_controllers, start_controllers_lengthT * sizeof(char*)); + offset += 3; + start_controllers_length = start_controllers_lengthT; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_st_start_controllers; + memcpy(&length_st_start_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_start_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_start_controllers-1]=0; + this->st_start_controllers = (char *)(inbuffer + offset-1); + offset += length_st_start_controllers; + memcpy( &(this->start_controllers[i]), &(this->st_start_controllers), sizeof(char*)); + } + uint8_t stop_controllers_lengthT = *(inbuffer + offset++); + if(stop_controllers_lengthT > stop_controllers_length) + this->stop_controllers = (char**)realloc(this->stop_controllers, stop_controllers_lengthT * sizeof(char*)); + offset += 3; + stop_controllers_length = stop_controllers_lengthT; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_st_stop_controllers; + memcpy(&length_st_stop_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_stop_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_stop_controllers-1]=0; + this->st_stop_controllers = (char *)(inbuffer + offset-1); + offset += length_st_stop_controllers; + memcpy( &(this->stop_controllers[i]), &(this->st_stop_controllers), sizeof(char*)); + } + union { + int32_t real; + uint32_t base; + } u_strictness; + u_strictness.base = 0; + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->strictness = u_strictness.real; + offset += sizeof(this->strictness); + return offset; + } + + const char * getType(){ return SWITCHCONTROLLER; }; + const char * getMD5(){ return "434da54adc434a5af5743ed711fd6ba1"; }; + + }; + + class SwitchControllerResponse : public ros::Msg + { + public: + bool ok; + + SwitchControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return SWITCHCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class SwitchController { + public: + typedef SwitchControllerRequest Request; + typedef SwitchControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/UnloadController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_UnloadController_h +#define _ROS_SERVICE_UnloadController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char UNLOADCONTROLLER[] = "controller_manager_msgs/UnloadController"; + + class UnloadControllerRequest : public ros::Msg + { + public: + const char* name; + + UnloadControllerRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return UNLOADCONTROLLER; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class UnloadControllerResponse : public ros::Msg + { + public: + bool ok; + + UnloadControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return UNLOADCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class UnloadController { + public: + typedef UnloadControllerRequest Request; + typedef UnloadControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/costmap_2d/VoxelGrid.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,117 @@ +#ifndef _ROS_costmap_2d_VoxelGrid_h +#define _ROS_costmap_2d_VoxelGrid_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point32.h" +#include "geometry_msgs/Vector3.h" + +namespace costmap_2d +{ + + class VoxelGrid : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t data_length; + uint32_t st_data; + uint32_t * data; + geometry_msgs::Point32 origin; + geometry_msgs::Vector3 resolutions; + uint32_t size_x; + uint32_t size_y; + uint32_t size_z; + + VoxelGrid(): + header(), + data_length(0), data(NULL), + origin(), + resolutions(), + size_x(0), + size_y(0), + size_z(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + offset += this->origin.serialize(outbuffer + offset); + offset += this->resolutions.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->size_x >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size_x >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size_x >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size_x >> (8 * 3)) & 0xFF; + offset += sizeof(this->size_x); + *(outbuffer + offset + 0) = (this->size_y >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size_y >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size_y >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size_y >> (8 * 3)) & 0xFF; + offset += sizeof(this->size_y); + *(outbuffer + offset + 0) = (this->size_z >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size_z >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size_z >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size_z >> (8 * 3)) & 0xFF; + offset += sizeof(this->size_z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint32_t) (*(inbuffer + offset))); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t)); + } + offset += this->origin.deserialize(inbuffer + offset); + offset += this->resolutions.deserialize(inbuffer + offset); + this->size_x = ((uint32_t) (*(inbuffer + offset))); + this->size_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size_x); + this->size_y = ((uint32_t) (*(inbuffer + offset))); + this->size_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size_y); + this->size_z = ((uint32_t) (*(inbuffer + offset))); + this->size_z |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size_z |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size_z |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size_z); + return offset; + } + + const char * getType(){ return "costmap_2d/VoxelGrid"; }; + const char * getMD5(){ return "48a040827e1322073d78ece5a497029c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/diagnostic_msgs/DiagnosticArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_diagnostic_msgs_DiagnosticArray_h +#define _ROS_diagnostic_msgs_DiagnosticArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "diagnostic_msgs/DiagnosticStatus.h" + +namespace diagnostic_msgs +{ + + class DiagnosticArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t status_length; + diagnostic_msgs::DiagnosticStatus st_status; + diagnostic_msgs::DiagnosticStatus * status; + + DiagnosticArray(): + header(), + status_length(0), status(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = status_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->status[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t status_lengthT = *(inbuffer + offset++); + if(status_lengthT > status_length) + this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus)); + offset += 3; + status_length = status_lengthT; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->st_status.deserialize(inbuffer + offset); + memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus)); + } + return offset; + } + + const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; }; + const char * getMD5(){ return "3cfbeff055e708a24c3d946a5c8139cd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/diagnostic_msgs/DiagnosticStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,127 @@ +#ifndef _ROS_diagnostic_msgs_DiagnosticStatus_h +#define _ROS_diagnostic_msgs_DiagnosticStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "diagnostic_msgs/KeyValue.h" + +namespace diagnostic_msgs +{ + + class DiagnosticStatus : public ros::Msg + { + public: + int8_t level; + const char* name; + const char* message; + const char* hardware_id; + uint8_t values_length; + diagnostic_msgs::KeyValue st_values; + diagnostic_msgs::KeyValue * values; + enum { OK = 0 }; + enum { WARN = 1 }; + enum { ERROR = 2 }; + + DiagnosticStatus(): + level(0), + name(""), + message(""), + hardware_id(""), + values_length(0), values(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_level; + u_level.real = this->level; + *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_message = strlen(this->message); + memcpy(outbuffer + offset, &length_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->message, length_message); + offset += length_message; + uint32_t length_hardware_id = strlen(this->hardware_id); + memcpy(outbuffer + offset, &length_hardware_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->hardware_id, length_hardware_id); + offset += length_hardware_id; + *(outbuffer + offset++) = values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < values_length; i++){ + offset += this->values[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_level; + u_level.base = 0; + u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->level = u_level.real; + offset += sizeof(this->level); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_message; + memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message-1]=0; + this->message = (char *)(inbuffer + offset-1); + offset += length_message; + uint32_t length_hardware_id; + memcpy(&length_hardware_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_hardware_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_hardware_id-1]=0; + this->hardware_id = (char *)(inbuffer + offset-1); + offset += length_hardware_id; + uint8_t values_lengthT = *(inbuffer + offset++); + if(values_lengthT > values_length) + this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue)); + offset += 3; + values_length = values_lengthT; + for( uint8_t i = 0; i < values_length; i++){ + offset += this->st_values.deserialize(inbuffer + offset); + memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue)); + } + return offset; + } + + const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; }; + const char * getMD5(){ return "67d15a62edb26e9d52b0f0efa3ef9da7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/diagnostic_msgs/KeyValue.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_diagnostic_msgs_KeyValue_h +#define _ROS_diagnostic_msgs_KeyValue_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace diagnostic_msgs +{ + + class KeyValue : public ros::Msg + { + public: + const char* key; + const char* value; + + KeyValue(): + key(""), + value("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_key = strlen(this->key); + memcpy(outbuffer + offset, &length_key, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->key, length_key); + offset += length_key; + uint32_t length_value = strlen(this->value); + memcpy(outbuffer + offset, &length_value, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->value, length_value); + offset += length_value; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_key; + memcpy(&length_key, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_key; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_key-1]=0; + this->key = (char *)(inbuffer + offset-1); + offset += length_key; + uint32_t length_value; + memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_value; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_value-1]=0; + this->value = (char *)(inbuffer + offset-1); + offset += length_value; + return offset; + } + + const char * getType(){ return "diagnostic_msgs/KeyValue"; }; + const char * getMD5(){ return "cf57fdc6617a881a88c16e768132149c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/diagnostic_msgs/SelfTest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,125 @@ +#ifndef _ROS_SERVICE_SelfTest_h +#define _ROS_SERVICE_SelfTest_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "diagnostic_msgs/DiagnosticStatus.h" + +namespace diagnostic_msgs +{ + +static const char SELFTEST[] = "diagnostic_msgs/SelfTest"; + + class SelfTestRequest : public ros::Msg + { + public: + + SelfTestRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SELFTEST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SelfTestResponse : public ros::Msg + { + public: + const char* id; + int8_t passed; + uint8_t status_length; + diagnostic_msgs::DiagnosticStatus st_status; + diagnostic_msgs::DiagnosticStatus * status; + + SelfTestResponse(): + id(""), + passed(0), + status_length(0), status(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + union { + int8_t real; + uint8_t base; + } u_passed; + u_passed.real = this->passed; + *(outbuffer + offset + 0) = (u_passed.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->passed); + *(outbuffer + offset++) = status_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->status[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + union { + int8_t real; + uint8_t base; + } u_passed; + u_passed.base = 0; + u_passed.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->passed = u_passed.real; + offset += sizeof(this->passed); + uint8_t status_lengthT = *(inbuffer + offset++); + if(status_lengthT > status_length) + this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus)); + offset += 3; + status_length = status_lengthT; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->st_status.deserialize(inbuffer + offset); + memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus)); + } + return offset; + } + + const char * getType(){ return SELFTEST; }; + const char * getMD5(){ return "74c9372c870a76da4fc2b3973978b898"; }; + + }; + + class SelfTest { + public: + typedef SelfTestRequest Request; + typedef SelfTestResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/driver_base/ConfigString.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_driver_base_ConfigString_h +#define _ROS_driver_base_ConfigString_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace driver_base +{ + + class ConfigString : public ros::Msg + { + public: + const char* name; + const char* value; + + ConfigString(): + name(""), + value("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_value = strlen(this->value); + memcpy(outbuffer + offset, &length_value, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->value, length_value); + offset += length_value; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_value; + memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_value; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_value-1]=0; + this->value = (char *)(inbuffer + offset-1); + offset += length_value; + return offset; + } + + const char * getType(){ return "driver_base/ConfigString"; }; + const char * getMD5(){ return "bc6ccc4a57f61779c8eaae61e9f422e0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/driver_base/ConfigValue.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_driver_base_ConfigValue_h +#define _ROS_driver_base_ConfigValue_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace driver_base +{ + + class ConfigValue : public ros::Msg + { + public: + const char* name; + float value; + + ConfigValue(): + name(""), + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += serializeAvrFloat64(outbuffer + offset, this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->value)); + return offset; + } + + const char * getType(){ return "driver_base/ConfigValue"; }; + const char * getMD5(){ return "d8512f27253c0f65f928a67c329cd658"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/driver_base/SensorLevels.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_driver_base_SensorLevels_h +#define _ROS_driver_base_SensorLevels_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace driver_base +{ + + class SensorLevels : public ros::Msg + { + public: + enum { RECONFIGURE_CLOSE = 3 }; + enum { RECONFIGURE_STOP = 1 }; + enum { RECONFIGURE_RUNNING = 0 }; + + SensorLevels() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "driver_base/SensorLevels"; }; + const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/duration.cpp Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include <math.h> +#include "ros/duration.h" + +namespace ros +{ + void normalizeSecNSecSigned(long &sec, long &nsec) + { + long nsec_part = nsec; + long sec_part = sec; + + while (nsec_part > 1000000000L) + { + nsec_part -= 1000000000L; + ++sec_part; + } + while (nsec_part < 0) + { + nsec_part += 1000000000L; + --sec_part; + } + sec = sec_part; + nsec = nsec_part; + } + + Duration& Duration::operator+=(const Duration &rhs) + { + sec += rhs.sec; + nsec += rhs.nsec; + normalizeSecNSecSigned(sec, nsec); + return *this; + } + + Duration& Duration::operator-=(const Duration &rhs){ + sec += -rhs.sec; + nsec += -rhs.nsec; + normalizeSecNSecSigned(sec, nsec); + return *this; + } + + Duration& Duration::operator*=(double scale){ + sec *= scale; + nsec *= scale; + normalizeSecNSecSigned(sec, nsec); + return *this; + } + +} +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/BoolParameter.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_dynamic_reconfigure_BoolParameter_h +#define _ROS_dynamic_reconfigure_BoolParameter_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class BoolParameter : public ros::Msg + { + public: + const char* name; + bool value; + + BoolParameter(): + name(""), + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + union { + bool real; + uint8_t base; + } u_value; + u_value.real = this->value; + *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + union { + bool real; + uint8_t base; + } u_value; + u_value.base = 0; + u_value.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->value = u_value.real; + offset += sizeof(this->value); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/BoolParameter"; }; + const char * getMD5(){ return "23f05028c1a699fb83e22401228c3a9e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/Config.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,143 @@ +#ifndef _ROS_dynamic_reconfigure_Config_h +#define _ROS_dynamic_reconfigure_Config_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "dynamic_reconfigure/BoolParameter.h" +#include "dynamic_reconfigure/IntParameter.h" +#include "dynamic_reconfigure/StrParameter.h" +#include "dynamic_reconfigure/DoubleParameter.h" +#include "dynamic_reconfigure/GroupState.h" + +namespace dynamic_reconfigure +{ + + class Config : public ros::Msg + { + public: + uint8_t bools_length; + dynamic_reconfigure::BoolParameter st_bools; + dynamic_reconfigure::BoolParameter * bools; + uint8_t ints_length; + dynamic_reconfigure::IntParameter st_ints; + dynamic_reconfigure::IntParameter * ints; + uint8_t strs_length; + dynamic_reconfigure::StrParameter st_strs; + dynamic_reconfigure::StrParameter * strs; + uint8_t doubles_length; + dynamic_reconfigure::DoubleParameter st_doubles; + dynamic_reconfigure::DoubleParameter * doubles; + uint8_t groups_length; + dynamic_reconfigure::GroupState st_groups; + dynamic_reconfigure::GroupState * groups; + + Config(): + bools_length(0), bools(NULL), + ints_length(0), ints(NULL), + strs_length(0), strs(NULL), + doubles_length(0), doubles(NULL), + groups_length(0), groups(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = bools_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < bools_length; i++){ + offset += this->bools[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = ints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ints_length; i++){ + offset += this->ints[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = strs_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < strs_length; i++){ + offset += this->strs[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = doubles_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < doubles_length; i++){ + offset += this->doubles[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = groups_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < groups_length; i++){ + offset += this->groups[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t bools_lengthT = *(inbuffer + offset++); + if(bools_lengthT > bools_length) + this->bools = (dynamic_reconfigure::BoolParameter*)realloc(this->bools, bools_lengthT * sizeof(dynamic_reconfigure::BoolParameter)); + offset += 3; + bools_length = bools_lengthT; + for( uint8_t i = 0; i < bools_length; i++){ + offset += this->st_bools.deserialize(inbuffer + offset); + memcpy( &(this->bools[i]), &(this->st_bools), sizeof(dynamic_reconfigure::BoolParameter)); + } + uint8_t ints_lengthT = *(inbuffer + offset++); + if(ints_lengthT > ints_length) + this->ints = (dynamic_reconfigure::IntParameter*)realloc(this->ints, ints_lengthT * sizeof(dynamic_reconfigure::IntParameter)); + offset += 3; + ints_length = ints_lengthT; + for( uint8_t i = 0; i < ints_length; i++){ + offset += this->st_ints.deserialize(inbuffer + offset); + memcpy( &(this->ints[i]), &(this->st_ints), sizeof(dynamic_reconfigure::IntParameter)); + } + uint8_t strs_lengthT = *(inbuffer + offset++); + if(strs_lengthT > strs_length) + this->strs = (dynamic_reconfigure::StrParameter*)realloc(this->strs, strs_lengthT * sizeof(dynamic_reconfigure::StrParameter)); + offset += 3; + strs_length = strs_lengthT; + for( uint8_t i = 0; i < strs_length; i++){ + offset += this->st_strs.deserialize(inbuffer + offset); + memcpy( &(this->strs[i]), &(this->st_strs), sizeof(dynamic_reconfigure::StrParameter)); + } + uint8_t doubles_lengthT = *(inbuffer + offset++); + if(doubles_lengthT > doubles_length) + this->doubles = (dynamic_reconfigure::DoubleParameter*)realloc(this->doubles, doubles_lengthT * sizeof(dynamic_reconfigure::DoubleParameter)); + offset += 3; + doubles_length = doubles_lengthT; + for( uint8_t i = 0; i < doubles_length; i++){ + offset += this->st_doubles.deserialize(inbuffer + offset); + memcpy( &(this->doubles[i]), &(this->st_doubles), sizeof(dynamic_reconfigure::DoubleParameter)); + } + uint8_t groups_lengthT = *(inbuffer + offset++); + if(groups_lengthT > groups_length) + this->groups = (dynamic_reconfigure::GroupState*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::GroupState)); + offset += 3; + groups_length = groups_lengthT; + for( uint8_t i = 0; i < groups_length; i++){ + offset += this->st_groups.deserialize(inbuffer + offset); + memcpy( &(this->groups[i]), &(this->st_groups), sizeof(dynamic_reconfigure::GroupState)); + } + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/Config"; }; + const char * getMD5(){ return "958f16a05573709014982821e6822580"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/ConfigDescription.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,72 @@ +#ifndef _ROS_dynamic_reconfigure_ConfigDescription_h +#define _ROS_dynamic_reconfigure_ConfigDescription_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "dynamic_reconfigure/Group.h" +#include "dynamic_reconfigure/Config.h" + +namespace dynamic_reconfigure +{ + + class ConfigDescription : public ros::Msg + { + public: + uint8_t groups_length; + dynamic_reconfigure::Group st_groups; + dynamic_reconfigure::Group * groups; + dynamic_reconfigure::Config max; + dynamic_reconfigure::Config min; + dynamic_reconfigure::Config dflt; + + ConfigDescription(): + groups_length(0), groups(NULL), + max(), + min(), + dflt() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = groups_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < groups_length; i++){ + offset += this->groups[i].serialize(outbuffer + offset); + } + offset += this->max.serialize(outbuffer + offset); + offset += this->min.serialize(outbuffer + offset); + offset += this->dflt.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t groups_lengthT = *(inbuffer + offset++); + if(groups_lengthT > groups_length) + this->groups = (dynamic_reconfigure::Group*)realloc(this->groups, groups_lengthT * sizeof(dynamic_reconfigure::Group)); + offset += 3; + groups_length = groups_lengthT; + for( uint8_t i = 0; i < groups_length; i++){ + offset += this->st_groups.deserialize(inbuffer + offset); + memcpy( &(this->groups[i]), &(this->st_groups), sizeof(dynamic_reconfigure::Group)); + } + offset += this->max.deserialize(inbuffer + offset); + offset += this->min.deserialize(inbuffer + offset); + offset += this->dflt.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/ConfigDescription"; }; + const char * getMD5(){ return "757ce9d44ba8ddd801bb30bc456f946f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/DoubleParameter.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_dynamic_reconfigure_DoubleParameter_h +#define _ROS_dynamic_reconfigure_DoubleParameter_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class DoubleParameter : public ros::Msg + { + public: + const char* name; + float value; + + DoubleParameter(): + name(""), + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += serializeAvrFloat64(outbuffer + offset, this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->value)); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/DoubleParameter"; }; + const char * getMD5(){ return "d8512f27253c0f65f928a67c329cd658"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/Group.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,137 @@ +#ifndef _ROS_dynamic_reconfigure_Group_h +#define _ROS_dynamic_reconfigure_Group_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "dynamic_reconfigure/ParamDescription.h" + +namespace dynamic_reconfigure +{ + + class Group : public ros::Msg + { + public: + const char* name; + const char* type; + uint8_t parameters_length; + dynamic_reconfigure::ParamDescription st_parameters; + dynamic_reconfigure::ParamDescription * parameters; + int32_t parent; + int32_t id; + + Group(): + name(""), + type(""), + parameters_length(0), parameters(NULL), + parent(0), + id(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + *(outbuffer + offset++) = parameters_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < parameters_length; i++){ + offset += this->parameters[i].serialize(outbuffer + offset); + } + union { + int32_t real; + uint32_t base; + } u_parent; + u_parent.real = this->parent; + *(outbuffer + offset + 0) = (u_parent.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_parent.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_parent.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_parent.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->parent); + union { + int32_t real; + uint32_t base; + } u_id; + u_id.real = this->id; + *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->id); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + uint8_t parameters_lengthT = *(inbuffer + offset++); + if(parameters_lengthT > parameters_length) + this->parameters = (dynamic_reconfigure::ParamDescription*)realloc(this->parameters, parameters_lengthT * sizeof(dynamic_reconfigure::ParamDescription)); + offset += 3; + parameters_length = parameters_lengthT; + for( uint8_t i = 0; i < parameters_length; i++){ + offset += this->st_parameters.deserialize(inbuffer + offset); + memcpy( &(this->parameters[i]), &(this->st_parameters), sizeof(dynamic_reconfigure::ParamDescription)); + } + union { + int32_t real; + uint32_t base; + } u_parent; + u_parent.base = 0; + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->parent = u_parent.real; + offset += sizeof(this->parent); + union { + int32_t real; + uint32_t base; + } u_id; + u_id.base = 0; + u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->id = u_id.real; + offset += sizeof(this->id); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/Group"; }; + const char * getMD5(){ return "9e8cd9e9423c94823db3614dd8b1cf7a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/GroupState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,117 @@ +#ifndef _ROS_dynamic_reconfigure_GroupState_h +#define _ROS_dynamic_reconfigure_GroupState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class GroupState : public ros::Msg + { + public: + const char* name; + bool state; + int32_t id; + int32_t parent; + + GroupState(): + name(""), + state(0), + id(0), + parent(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + union { + bool real; + uint8_t base; + } u_state; + u_state.real = this->state; + *(outbuffer + offset + 0) = (u_state.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->state); + union { + int32_t real; + uint32_t base; + } u_id; + u_id.real = this->id; + *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_parent; + u_parent.real = this->parent; + *(outbuffer + offset + 0) = (u_parent.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_parent.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_parent.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_parent.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->parent); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + union { + bool real; + uint8_t base; + } u_state; + u_state.base = 0; + u_state.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->state = u_state.real; + offset += sizeof(this->state); + union { + int32_t real; + uint32_t base; + } u_id; + u_id.base = 0; + u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->id = u_id.real; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_parent; + u_parent.base = 0; + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_parent.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->parent = u_parent.real; + offset += sizeof(this->parent); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/GroupState"; }; + const char * getMD5(){ return "a2d87f51dc22930325041a2f8b1571f8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/IntParameter.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_dynamic_reconfigure_IntParameter_h +#define _ROS_dynamic_reconfigure_IntParameter_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class IntParameter : public ros::Msg + { + public: + const char* name; + int32_t value; + + IntParameter(): + name(""), + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.real = this->value; + *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.base = 0; + u_value.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->value = u_value.real; + offset += sizeof(this->value); + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/IntParameter"; }; + const char * getMD5(){ return "65fedc7a0cbfb8db035e46194a350bf1"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/ParamDescription.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,114 @@ +#ifndef _ROS_dynamic_reconfigure_ParamDescription_h +#define _ROS_dynamic_reconfigure_ParamDescription_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class ParamDescription : public ros::Msg + { + public: + const char* name; + const char* type; + uint32_t level; + const char* description; + const char* edit_method; + + ParamDescription(): + name(""), + type(""), + level(0), + description(""), + edit_method("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->level >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->level >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->level >> (8 * 3)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_description = strlen(this->description); + memcpy(outbuffer + offset, &length_description, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->description, length_description); + offset += length_description; + uint32_t length_edit_method = strlen(this->edit_method); + memcpy(outbuffer + offset, &length_edit_method, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->edit_method, length_edit_method); + offset += length_edit_method; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + this->level = ((uint32_t) (*(inbuffer + offset))); + this->level |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->level |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->level |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->level); + uint32_t length_description; + memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_description; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_description-1]=0; + this->description = (char *)(inbuffer + offset-1); + offset += length_description; + uint32_t length_edit_method; + memcpy(&length_edit_method, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_edit_method; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_edit_method-1]=0; + this->edit_method = (char *)(inbuffer + offset-1); + offset += length_edit_method; + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/ParamDescription"; }; + const char * getMD5(){ return "7434fcb9348c13054e0c3b267c8cb34d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/Reconfigure.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_SERVICE_Reconfigure_h +#define _ROS_SERVICE_Reconfigure_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "dynamic_reconfigure/Config.h" + +namespace dynamic_reconfigure +{ + +static const char RECONFIGURE[] = "dynamic_reconfigure/Reconfigure"; + + class ReconfigureRequest : public ros::Msg + { + public: + dynamic_reconfigure::Config config; + + ReconfigureRequest(): + config() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->config.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->config.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return RECONFIGURE; }; + const char * getMD5(){ return "ac41a77620a4a0348b7001641796a8a1"; }; + + }; + + class ReconfigureResponse : public ros::Msg + { + public: + dynamic_reconfigure::Config config; + + ReconfigureResponse(): + config() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->config.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->config.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return RECONFIGURE; }; + const char * getMD5(){ return "ac41a77620a4a0348b7001641796a8a1"; }; + + }; + + class Reconfigure { + public: + typedef ReconfigureRequest Request; + typedef ReconfigureResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/SensorLevels.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_dynamic_reconfigure_SensorLevels_h +#define _ROS_dynamic_reconfigure_SensorLevels_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class SensorLevels : public ros::Msg + { + public: + enum { RECONFIGURE_CLOSE = 3 }; + enum { RECONFIGURE_STOP = 1 }; + enum { RECONFIGURE_RUNNING = 0 }; + + SensorLevels() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/SensorLevels"; }; + const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dynamic_reconfigure/StrParameter.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_dynamic_reconfigure_StrParameter_h +#define _ROS_dynamic_reconfigure_StrParameter_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace dynamic_reconfigure +{ + + class StrParameter : public ros::Msg + { + public: + const char* name; + const char* value; + + StrParameter(): + name(""), + value("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_value = strlen(this->value); + memcpy(outbuffer + offset, &length_value, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->value, length_value); + offset += length_value; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_value; + memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_value; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_value-1]=0; + this->value = (char *)(inbuffer + offset-1); + offset += length_value; + return offset; + } + + const char * getType(){ return "dynamic_reconfigure/StrParameter"; }; + const char * getMD5(){ return "bc6ccc4a57f61779c8eaae61e9f422e0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ApplyBodyWrench.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,192 @@ +#ifndef _ROS_SERVICE_ApplyBodyWrench_h +#define _ROS_SERVICE_ApplyBodyWrench_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" +#include "geometry_msgs/Wrench.h" +#include "ros/time.h" +#include "geometry_msgs/Point.h" + +namespace gazebo_msgs +{ + +static const char APPLYBODYWRENCH[] = "gazebo_msgs/ApplyBodyWrench"; + + class ApplyBodyWrenchRequest : public ros::Msg + { + public: + const char* body_name; + const char* reference_frame; + geometry_msgs::Point reference_point; + geometry_msgs::Wrench wrench; + ros::Time start_time; + ros::Duration duration; + + ApplyBodyWrenchRequest(): + body_name(""), + reference_frame(""), + reference_point(), + wrench(), + start_time(), + duration() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_body_name = strlen(this->body_name); + memcpy(outbuffer + offset, &length_body_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->body_name, length_body_name); + offset += length_body_name; + uint32_t length_reference_frame = strlen(this->reference_frame); + memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); + offset += length_reference_frame; + offset += this->reference_point.serialize(outbuffer + offset); + offset += this->wrench.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->start_time.sec); + *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->start_time.nsec); + *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->duration.sec); + *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->duration.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_body_name; + memcpy(&length_body_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_body_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_body_name-1]=0; + this->body_name = (char *)(inbuffer + offset-1); + offset += length_body_name; + uint32_t length_reference_frame; + memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame-1]=0; + this->reference_frame = (char *)(inbuffer + offset-1); + offset += length_reference_frame; + offset += this->reference_point.deserialize(inbuffer + offset); + offset += this->wrench.deserialize(inbuffer + offset); + this->start_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->start_time.sec); + this->start_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->start_time.nsec); + this->duration.sec = ((uint32_t) (*(inbuffer + offset))); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->duration.sec); + this->duration.nsec = ((uint32_t) (*(inbuffer + offset))); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->duration.nsec); + return offset; + } + + const char * getType(){ return APPLYBODYWRENCH; }; + const char * getMD5(){ return "e37e6adf97eba5095baa77dffb71e5bd"; }; + + }; + + class ApplyBodyWrenchResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + ApplyBodyWrenchResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return APPLYBODYWRENCH; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class ApplyBodyWrench { + public: + typedef ApplyBodyWrenchRequest Request; + typedef ApplyBodyWrenchResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ApplyJointEffort.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,170 @@ +#ifndef _ROS_SERVICE_ApplyJointEffort_h +#define _ROS_SERVICE_ApplyJointEffort_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" +#include "ros/time.h" + +namespace gazebo_msgs +{ + +static const char APPLYJOINTEFFORT[] = "gazebo_msgs/ApplyJointEffort"; + + class ApplyJointEffortRequest : public ros::Msg + { + public: + const char* joint_name; + float effort; + ros::Time start_time; + ros::Duration duration; + + ApplyJointEffortRequest(): + joint_name(""), + effort(0), + start_time(), + duration() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + offset += serializeAvrFloat64(outbuffer + offset, this->effort); + *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->start_time.sec); + *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->start_time.nsec); + *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->duration.sec); + *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->duration.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->effort)); + this->start_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->start_time.sec); + this->start_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->start_time.nsec); + this->duration.sec = ((uint32_t) (*(inbuffer + offset))); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->duration.sec); + this->duration.nsec = ((uint32_t) (*(inbuffer + offset))); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->duration.nsec); + return offset; + } + + const char * getType(){ return APPLYJOINTEFFORT; }; + const char * getMD5(){ return "2c3396ab9af67a509ecd2167a8fe41a2"; }; + + }; + + class ApplyJointEffortResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + ApplyJointEffortResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return APPLYJOINTEFFORT; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class ApplyJointEffort { + public: + typedef ApplyJointEffortRequest Request; + typedef ApplyJointEffortResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/BodyRequest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_BodyRequest_h +#define _ROS_SERVICE_BodyRequest_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char BODYREQUEST[] = "gazebo_msgs/BodyRequest"; + + class BodyRequestRequest : public ros::Msg + { + public: + const char* body_name; + + BodyRequestRequest(): + body_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_body_name = strlen(this->body_name); + memcpy(outbuffer + offset, &length_body_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->body_name, length_body_name); + offset += length_body_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_body_name; + memcpy(&length_body_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_body_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_body_name-1]=0; + this->body_name = (char *)(inbuffer + offset-1); + offset += length_body_name; + return offset; + } + + const char * getType(){ return BODYREQUEST; }; + const char * getMD5(){ return "5eade9afe7f232d78005bd0cafeab755"; }; + + }; + + class BodyRequestResponse : public ros::Msg + { + public: + + BodyRequestResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return BODYREQUEST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class BodyRequest { + public: + typedef BodyRequestRequest Request; + typedef BodyRequestResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ContactState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,172 @@ +#ifndef _ROS_gazebo_msgs_ContactState_h +#define _ROS_gazebo_msgs_ContactState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Wrench.h" +#include "geometry_msgs/Vector3.h" + +namespace gazebo_msgs +{ + + class ContactState : public ros::Msg + { + public: + const char* info; + const char* collision1_name; + const char* collision2_name; + uint8_t wrenches_length; + geometry_msgs::Wrench st_wrenches; + geometry_msgs::Wrench * wrenches; + geometry_msgs::Wrench total_wrench; + uint8_t contact_positions_length; + geometry_msgs::Vector3 st_contact_positions; + geometry_msgs::Vector3 * contact_positions; + uint8_t contact_normals_length; + geometry_msgs::Vector3 st_contact_normals; + geometry_msgs::Vector3 * contact_normals; + uint8_t depths_length; + float st_depths; + float * depths; + + ContactState(): + info(""), + collision1_name(""), + collision2_name(""), + wrenches_length(0), wrenches(NULL), + total_wrench(), + contact_positions_length(0), contact_positions(NULL), + contact_normals_length(0), contact_normals(NULL), + depths_length(0), depths(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_info = strlen(this->info); + memcpy(outbuffer + offset, &length_info, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->info, length_info); + offset += length_info; + uint32_t length_collision1_name = strlen(this->collision1_name); + memcpy(outbuffer + offset, &length_collision1_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision1_name, length_collision1_name); + offset += length_collision1_name; + uint32_t length_collision2_name = strlen(this->collision2_name); + memcpy(outbuffer + offset, &length_collision2_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision2_name, length_collision2_name); + offset += length_collision2_name; + *(outbuffer + offset++) = wrenches_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < wrenches_length; i++){ + offset += this->wrenches[i].serialize(outbuffer + offset); + } + offset += this->total_wrench.serialize(outbuffer + offset); + *(outbuffer + offset++) = contact_positions_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < contact_positions_length; i++){ + offset += this->contact_positions[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = contact_normals_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < contact_normals_length; i++){ + offset += this->contact_normals[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = depths_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < depths_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->depths[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_info; + memcpy(&length_info, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_info; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_info-1]=0; + this->info = (char *)(inbuffer + offset-1); + offset += length_info; + uint32_t length_collision1_name; + memcpy(&length_collision1_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision1_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision1_name-1]=0; + this->collision1_name = (char *)(inbuffer + offset-1); + offset += length_collision1_name; + uint32_t length_collision2_name; + memcpy(&length_collision2_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision2_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision2_name-1]=0; + this->collision2_name = (char *)(inbuffer + offset-1); + offset += length_collision2_name; + uint8_t wrenches_lengthT = *(inbuffer + offset++); + if(wrenches_lengthT > wrenches_length) + this->wrenches = (geometry_msgs::Wrench*)realloc(this->wrenches, wrenches_lengthT * sizeof(geometry_msgs::Wrench)); + offset += 3; + wrenches_length = wrenches_lengthT; + for( uint8_t i = 0; i < wrenches_length; i++){ + offset += this->st_wrenches.deserialize(inbuffer + offset); + memcpy( &(this->wrenches[i]), &(this->st_wrenches), sizeof(geometry_msgs::Wrench)); + } + offset += this->total_wrench.deserialize(inbuffer + offset); + uint8_t contact_positions_lengthT = *(inbuffer + offset++); + if(contact_positions_lengthT > contact_positions_length) + this->contact_positions = (geometry_msgs::Vector3*)realloc(this->contact_positions, contact_positions_lengthT * sizeof(geometry_msgs::Vector3)); + offset += 3; + contact_positions_length = contact_positions_lengthT; + for( uint8_t i = 0; i < contact_positions_length; i++){ + offset += this->st_contact_positions.deserialize(inbuffer + offset); + memcpy( &(this->contact_positions[i]), &(this->st_contact_positions), sizeof(geometry_msgs::Vector3)); + } + uint8_t contact_normals_lengthT = *(inbuffer + offset++); + if(contact_normals_lengthT > contact_normals_length) + this->contact_normals = (geometry_msgs::Vector3*)realloc(this->contact_normals, contact_normals_lengthT * sizeof(geometry_msgs::Vector3)); + offset += 3; + contact_normals_length = contact_normals_lengthT; + for( uint8_t i = 0; i < contact_normals_length; i++){ + offset += this->st_contact_normals.deserialize(inbuffer + offset); + memcpy( &(this->contact_normals[i]), &(this->st_contact_normals), sizeof(geometry_msgs::Vector3)); + } + uint8_t depths_lengthT = *(inbuffer + offset++); + if(depths_lengthT > depths_length) + this->depths = (float*)realloc(this->depths, depths_lengthT * sizeof(float)); + offset += 3; + depths_length = depths_lengthT; + for( uint8_t i = 0; i < depths_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_depths)); + memcpy( &(this->depths[i]), &(this->st_depths), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/ContactState"; }; + const char * getMD5(){ return "48c0ffb054b8c444f870cecea1ee50d9"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ContactsState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_gazebo_msgs_ContactsState_h +#define _ROS_gazebo_msgs_ContactsState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "gazebo_msgs/ContactState.h" + +namespace gazebo_msgs +{ + + class ContactsState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t states_length; + gazebo_msgs::ContactState st_states; + gazebo_msgs::ContactState * states; + + ContactsState(): + header(), + states_length(0), states(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < states_length; i++){ + offset += this->states[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t states_lengthT = *(inbuffer + offset++); + if(states_lengthT > states_length) + this->states = (gazebo_msgs::ContactState*)realloc(this->states, states_lengthT * sizeof(gazebo_msgs::ContactState)); + offset += 3; + states_length = states_lengthT; + for( uint8_t i = 0; i < states_length; i++){ + offset += this->st_states.deserialize(inbuffer + offset); + memcpy( &(this->states[i]), &(this->st_states), sizeof(gazebo_msgs::ContactState)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/ContactsState"; }; + const char * getMD5(){ return "acbcb1601a8e525bf72509f18e6f668d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/DeleteModel.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,120 @@ +#ifndef _ROS_SERVICE_DeleteModel_h +#define _ROS_SERVICE_DeleteModel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char DELETEMODEL[] = "gazebo_msgs/DeleteModel"; + + class DeleteModelRequest : public ros::Msg + { + public: + const char* model_name; + + DeleteModelRequest(): + model_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + return offset; + } + + const char * getType(){ return DELETEMODEL; }; + const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; }; + + }; + + class DeleteModelResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + DeleteModelResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return DELETEMODEL; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class DeleteModel { + public: + typedef DeleteModelRequest Request; + typedef DeleteModelResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetJointProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,192 @@ +#ifndef _ROS_SERVICE_GetJointProperties_h +#define _ROS_SERVICE_GetJointProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char GETJOINTPROPERTIES[] = "gazebo_msgs/GetJointProperties"; + + class GetJointPropertiesRequest : public ros::Msg + { + public: + const char* joint_name; + + GetJointPropertiesRequest(): + joint_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + return offset; + } + + const char * getType(){ return GETJOINTPROPERTIES; }; + const char * getMD5(){ return "0be1351618e1dc030eb7959d9a4902de"; }; + + }; + + class GetJointPropertiesResponse : public ros::Msg + { + public: + uint8_t type; + uint8_t damping_length; + float st_damping; + float * damping; + uint8_t position_length; + float st_position; + float * position; + uint8_t rate_length; + float st_rate; + float * rate; + bool success; + const char* status_message; + enum { REVOLUTE = 0 }; + enum { CONTINUOUS = 1 }; + enum { PRISMATIC = 2 }; + enum { FIXED = 3 }; + enum { BALL = 4 }; + enum { UNIVERSAL = 5 }; + + GetJointPropertiesResponse(): + type(0), + damping_length(0), damping(NULL), + position_length(0), position(NULL), + rate_length(0), rate(NULL), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; + offset += sizeof(this->type); + *(outbuffer + offset++) = damping_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < damping_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->damping[i]); + } + *(outbuffer + offset++) = position_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < position_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->position[i]); + } + *(outbuffer + offset++) = rate_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < rate_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->rate[i]); + } + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->type); + uint8_t damping_lengthT = *(inbuffer + offset++); + if(damping_lengthT > damping_length) + this->damping = (float*)realloc(this->damping, damping_lengthT * sizeof(float)); + offset += 3; + damping_length = damping_lengthT; + for( uint8_t i = 0; i < damping_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_damping)); + memcpy( &(this->damping[i]), &(this->st_damping), sizeof(float)); + } + uint8_t position_lengthT = *(inbuffer + offset++); + if(position_lengthT > position_length) + this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); + offset += 3; + position_length = position_lengthT; + for( uint8_t i = 0; i < position_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_position)); + memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); + } + uint8_t rate_lengthT = *(inbuffer + offset++); + if(rate_lengthT > rate_length) + this->rate = (float*)realloc(this->rate, rate_lengthT * sizeof(float)); + offset += 3; + rate_length = rate_lengthT; + for( uint8_t i = 0; i < rate_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_rate)); + memcpy( &(this->rate[i]), &(this->st_rate), sizeof(float)); + } + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETJOINTPROPERTIES; }; + const char * getMD5(){ return "cd7b30a39faa372283dc94c5f6457f82"; }; + + }; + + class GetJointProperties { + public: + typedef GetJointPropertiesRequest Request; + typedef GetJointPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetLinkProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,170 @@ +#ifndef _ROS_SERVICE_GetLinkProperties_h +#define _ROS_SERVICE_GetLinkProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" + +namespace gazebo_msgs +{ + +static const char GETLINKPROPERTIES[] = "gazebo_msgs/GetLinkProperties"; + + class GetLinkPropertiesRequest : public ros::Msg + { + public: + const char* link_name; + + GetLinkPropertiesRequest(): + link_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + return offset; + } + + const char * getType(){ return GETLINKPROPERTIES; }; + const char * getMD5(){ return "7d82d60381f1b66a30f2157f60884345"; }; + + }; + + class GetLinkPropertiesResponse : public ros::Msg + { + public: + geometry_msgs::Pose com; + bool gravity_mode; + float mass; + float ixx; + float ixy; + float ixz; + float iyy; + float iyz; + float izz; + bool success; + const char* status_message; + + GetLinkPropertiesResponse(): + com(), + gravity_mode(0), + mass(0), + ixx(0), + ixy(0), + ixz(0), + iyy(0), + iyz(0), + izz(0), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->com.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_gravity_mode; + u_gravity_mode.real = this->gravity_mode; + *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->gravity_mode); + offset += serializeAvrFloat64(outbuffer + offset, this->mass); + offset += serializeAvrFloat64(outbuffer + offset, this->ixx); + offset += serializeAvrFloat64(outbuffer + offset, this->ixy); + offset += serializeAvrFloat64(outbuffer + offset, this->ixz); + offset += serializeAvrFloat64(outbuffer + offset, this->iyy); + offset += serializeAvrFloat64(outbuffer + offset, this->iyz); + offset += serializeAvrFloat64(outbuffer + offset, this->izz); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->com.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_gravity_mode; + u_gravity_mode.base = 0; + u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->gravity_mode = u_gravity_mode.real; + offset += sizeof(this->gravity_mode); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->mass)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixx)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixy)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixz)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyy)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyz)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->izz)); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETLINKPROPERTIES; }; + const char * getMD5(){ return "a8619f92d17cfcc3958c0fd13299443d"; }; + + }; + + class GetLinkProperties { + public: + typedef GetLinkPropertiesRequest Request; + typedef GetLinkPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetLinkState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,141 @@ +#ifndef _ROS_SERVICE_GetLinkState_h +#define _ROS_SERVICE_GetLinkState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "gazebo_msgs/LinkState.h" + +namespace gazebo_msgs +{ + +static const char GETLINKSTATE[] = "gazebo_msgs/GetLinkState"; + + class GetLinkStateRequest : public ros::Msg + { + public: + const char* link_name; + const char* reference_frame; + + GetLinkStateRequest(): + link_name(""), + reference_frame("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + uint32_t length_reference_frame = strlen(this->reference_frame); + memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); + offset += length_reference_frame; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + uint32_t length_reference_frame; + memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame-1]=0; + this->reference_frame = (char *)(inbuffer + offset-1); + offset += length_reference_frame; + return offset; + } + + const char * getType(){ return GETLINKSTATE; }; + const char * getMD5(){ return "7551675c30aaa71f7c288d4864552001"; }; + + }; + + class GetLinkStateResponse : public ros::Msg + { + public: + gazebo_msgs::LinkState link_state; + bool success; + const char* status_message; + + GetLinkStateResponse(): + link_state(), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->link_state.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->link_state.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETLINKSTATE; }; + const char * getMD5(){ return "8ba55ad34f9c072e75c0de57b089753b"; }; + + }; + + class GetLinkState { + public: + typedef GetLinkStateRequest Request; + typedef GetLinkStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetModelProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,297 @@ +#ifndef _ROS_SERVICE_GetModelProperties_h +#define _ROS_SERVICE_GetModelProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char GETMODELPROPERTIES[] = "gazebo_msgs/GetModelProperties"; + + class GetModelPropertiesRequest : public ros::Msg + { + public: + const char* model_name; + + GetModelPropertiesRequest(): + model_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + return offset; + } + + const char * getType(){ return GETMODELPROPERTIES; }; + const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; }; + + }; + + class GetModelPropertiesResponse : public ros::Msg + { + public: + const char* parent_model_name; + const char* canonical_body_name; + uint8_t body_names_length; + char* st_body_names; + char* * body_names; + uint8_t geom_names_length; + char* st_geom_names; + char* * geom_names; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t child_model_names_length; + char* st_child_model_names; + char* * child_model_names; + bool is_static; + bool success; + const char* status_message; + + GetModelPropertiesResponse(): + parent_model_name(""), + canonical_body_name(""), + body_names_length(0), body_names(NULL), + geom_names_length(0), geom_names(NULL), + joint_names_length(0), joint_names(NULL), + child_model_names_length(0), child_model_names(NULL), + is_static(0), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_parent_model_name = strlen(this->parent_model_name); + memcpy(outbuffer + offset, &length_parent_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->parent_model_name, length_parent_model_name); + offset += length_parent_model_name; + uint32_t length_canonical_body_name = strlen(this->canonical_body_name); + memcpy(outbuffer + offset, &length_canonical_body_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->canonical_body_name, length_canonical_body_name); + offset += length_canonical_body_name; + *(outbuffer + offset++) = body_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < body_names_length; i++){ + uint32_t length_body_namesi = strlen(this->body_names[i]); + memcpy(outbuffer + offset, &length_body_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->body_names[i], length_body_namesi); + offset += length_body_namesi; + } + *(outbuffer + offset++) = geom_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < geom_names_length; i++){ + uint32_t length_geom_namesi = strlen(this->geom_names[i]); + memcpy(outbuffer + offset, &length_geom_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->geom_names[i], length_geom_namesi); + offset += length_geom_namesi; + } + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = child_model_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < child_model_names_length; i++){ + uint32_t length_child_model_namesi = strlen(this->child_model_names[i]); + memcpy(outbuffer + offset, &length_child_model_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->child_model_names[i], length_child_model_namesi); + offset += length_child_model_namesi; + } + union { + bool real; + uint8_t base; + } u_is_static; + u_is_static.real = this->is_static; + *(outbuffer + offset + 0) = (u_is_static.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_static); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_parent_model_name; + memcpy(&length_parent_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_parent_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_parent_model_name-1]=0; + this->parent_model_name = (char *)(inbuffer + offset-1); + offset += length_parent_model_name; + uint32_t length_canonical_body_name; + memcpy(&length_canonical_body_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_canonical_body_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_canonical_body_name-1]=0; + this->canonical_body_name = (char *)(inbuffer + offset-1); + offset += length_canonical_body_name; + uint8_t body_names_lengthT = *(inbuffer + offset++); + if(body_names_lengthT > body_names_length) + this->body_names = (char**)realloc(this->body_names, body_names_lengthT * sizeof(char*)); + offset += 3; + body_names_length = body_names_lengthT; + for( uint8_t i = 0; i < body_names_length; i++){ + uint32_t length_st_body_names; + memcpy(&length_st_body_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_body_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_body_names-1]=0; + this->st_body_names = (char *)(inbuffer + offset-1); + offset += length_st_body_names; + memcpy( &(this->body_names[i]), &(this->st_body_names), sizeof(char*)); + } + uint8_t geom_names_lengthT = *(inbuffer + offset++); + if(geom_names_lengthT > geom_names_length) + this->geom_names = (char**)realloc(this->geom_names, geom_names_lengthT * sizeof(char*)); + offset += 3; + geom_names_length = geom_names_lengthT; + for( uint8_t i = 0; i < geom_names_length; i++){ + uint32_t length_st_geom_names; + memcpy(&length_st_geom_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_geom_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_geom_names-1]=0; + this->st_geom_names = (char *)(inbuffer + offset-1); + offset += length_st_geom_names; + memcpy( &(this->geom_names[i]), &(this->st_geom_names), sizeof(char*)); + } + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t child_model_names_lengthT = *(inbuffer + offset++); + if(child_model_names_lengthT > child_model_names_length) + this->child_model_names = (char**)realloc(this->child_model_names, child_model_names_lengthT * sizeof(char*)); + offset += 3; + child_model_names_length = child_model_names_lengthT; + for( uint8_t i = 0; i < child_model_names_length; i++){ + uint32_t length_st_child_model_names; + memcpy(&length_st_child_model_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_child_model_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_child_model_names-1]=0; + this->st_child_model_names = (char *)(inbuffer + offset-1); + offset += length_st_child_model_names; + memcpy( &(this->child_model_names[i]), &(this->st_child_model_names), sizeof(char*)); + } + union { + bool real; + uint8_t base; + } u_is_static; + u_is_static.base = 0; + u_is_static.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_static = u_is_static.real; + offset += sizeof(this->is_static); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETMODELPROPERTIES; }; + const char * getMD5(){ return "b7f370938ef77b464b95f1bab3ec5028"; }; + + }; + + class GetModelProperties { + public: + typedef GetModelPropertiesRequest Request; + typedef GetModelPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetModelState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,146 @@ +#ifndef _ROS_SERVICE_GetModelState_h +#define _ROS_SERVICE_GetModelState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + +static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState"; + + class GetModelStateRequest : public ros::Msg + { + public: + const char* model_name; + const char* relative_entity_name; + + GetModelStateRequest(): + model_name(""), + relative_entity_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + uint32_t length_relative_entity_name = strlen(this->relative_entity_name); + memcpy(outbuffer + offset, &length_relative_entity_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name); + offset += length_relative_entity_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + uint32_t length_relative_entity_name; + memcpy(&length_relative_entity_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_relative_entity_name-1]=0; + this->relative_entity_name = (char *)(inbuffer + offset-1); + offset += length_relative_entity_name; + return offset; + } + + const char * getType(){ return GETMODELSTATE; }; + const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; }; + + }; + + class GetModelStateResponse : public ros::Msg + { + public: + geometry_msgs::Pose pose; + geometry_msgs::Twist twist; + bool success; + const char* status_message; + + GetModelStateResponse(): + pose(), + twist(), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->pose.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETMODELSTATE; }; + const char * getMD5(){ return "1f8f991dc94e0cb27fe61383e0f576bb"; }; + + }; + + class GetModelState { + public: + typedef GetModelStateRequest Request; + typedef GetModelStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetPhysicsProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,139 @@ +#ifndef _ROS_SERVICE_GetPhysicsProperties_h +#define _ROS_SERVICE_GetPhysicsProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" +#include "gazebo_msgs/ODEPhysics.h" + +namespace gazebo_msgs +{ + +static const char GETPHYSICSPROPERTIES[] = "gazebo_msgs/GetPhysicsProperties"; + + class GetPhysicsPropertiesRequest : public ros::Msg + { + public: + + GetPhysicsPropertiesRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETPHYSICSPROPERTIES; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetPhysicsPropertiesResponse : public ros::Msg + { + public: + float time_step; + bool pause; + float max_update_rate; + geometry_msgs::Vector3 gravity; + gazebo_msgs::ODEPhysics ode_config; + bool success; + const char* status_message; + + GetPhysicsPropertiesResponse(): + time_step(0), + pause(0), + max_update_rate(0), + gravity(), + ode_config(), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->time_step); + union { + bool real; + uint8_t base; + } u_pause; + u_pause.real = this->pause; + *(outbuffer + offset + 0) = (u_pause.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->pause); + offset += serializeAvrFloat64(outbuffer + offset, this->max_update_rate); + offset += this->gravity.serialize(outbuffer + offset); + offset += this->ode_config.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->time_step)); + union { + bool real; + uint8_t base; + } u_pause; + u_pause.base = 0; + u_pause.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->pause = u_pause.real; + offset += sizeof(this->pause); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_update_rate)); + offset += this->gravity.deserialize(inbuffer + offset); + offset += this->ode_config.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETPHYSICSPROPERTIES; }; + const char * getMD5(){ return "575a5e74786981b7df2e3afc567693a6"; }; + + }; + + class GetPhysicsProperties { + public: + typedef GetPhysicsPropertiesRequest Request; + typedef GetPhysicsPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/GetWorldProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,157 @@ +#ifndef _ROS_SERVICE_GetWorldProperties_h +#define _ROS_SERVICE_GetWorldProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char GETWORLDPROPERTIES[] = "gazebo_msgs/GetWorldProperties"; + + class GetWorldPropertiesRequest : public ros::Msg + { + public: + + GetWorldPropertiesRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETWORLDPROPERTIES; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetWorldPropertiesResponse : public ros::Msg + { + public: + float sim_time; + uint8_t model_names_length; + char* st_model_names; + char* * model_names; + bool rendering_enabled; + bool success; + const char* status_message; + + GetWorldPropertiesResponse(): + sim_time(0), + model_names_length(0), model_names(NULL), + rendering_enabled(0), + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->sim_time); + *(outbuffer + offset++) = model_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < model_names_length; i++){ + uint32_t length_model_namesi = strlen(this->model_names[i]); + memcpy(outbuffer + offset, &length_model_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_names[i], length_model_namesi); + offset += length_model_namesi; + } + union { + bool real; + uint8_t base; + } u_rendering_enabled; + u_rendering_enabled.real = this->rendering_enabled; + *(outbuffer + offset + 0) = (u_rendering_enabled.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->rendering_enabled); + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->sim_time)); + uint8_t model_names_lengthT = *(inbuffer + offset++); + if(model_names_lengthT > model_names_length) + this->model_names = (char**)realloc(this->model_names, model_names_lengthT * sizeof(char*)); + offset += 3; + model_names_length = model_names_lengthT; + for( uint8_t i = 0; i < model_names_length; i++){ + uint32_t length_st_model_names; + memcpy(&length_st_model_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_model_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_model_names-1]=0; + this->st_model_names = (char *)(inbuffer + offset-1); + offset += length_st_model_names; + memcpy( &(this->model_names[i]), &(this->st_model_names), sizeof(char*)); + } + union { + bool real; + uint8_t base; + } u_rendering_enabled; + u_rendering_enabled.base = 0; + u_rendering_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->rendering_enabled = u_rendering_enabled.real; + offset += sizeof(this->rendering_enabled); + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return GETWORLDPROPERTIES; }; + const char * getMD5(){ return "36bb0f2eccf4d8be971410c22818ba3f"; }; + + }; + + class GetWorldProperties { + public: + typedef GetWorldPropertiesRequest Request; + typedef GetWorldPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/JointRequest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_JointRequest_h +#define _ROS_SERVICE_JointRequest_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char JOINTREQUEST[] = "gazebo_msgs/JointRequest"; + + class JointRequestRequest : public ros::Msg + { + public: + const char* joint_name; + + JointRequestRequest(): + joint_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + return offset; + } + + const char * getType(){ return JOINTREQUEST; }; + const char * getMD5(){ return "0be1351618e1dc030eb7959d9a4902de"; }; + + }; + + class JointRequestResponse : public ros::Msg + { + public: + + JointRequestResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return JOINTREQUEST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class JointRequest { + public: + typedef JointRequestRequest Request; + typedef JointRequestResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/LinkState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_gazebo_msgs_LinkState_h +#define _ROS_gazebo_msgs_LinkState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + + class LinkState : public ros::Msg + { + public: + const char* link_name; + geometry_msgs::Pose pose; + geometry_msgs::Twist twist; + const char* reference_frame; + + LinkState(): + link_name(""), + pose(), + twist(), + reference_frame("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += this->pose.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + uint32_t length_reference_frame = strlen(this->reference_frame); + memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); + offset += length_reference_frame; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + uint32_t length_reference_frame; + memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame-1]=0; + this->reference_frame = (char *)(inbuffer + offset-1); + offset += length_reference_frame; + return offset; + } + + const char * getType(){ return "gazebo_msgs/LinkState"; }; + const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/LinkStates.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_gazebo_msgs_LinkStates_h +#define _ROS_gazebo_msgs_LinkStates_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + + class LinkStates : public ros::Msg + { + public: + uint8_t name_length; + char* st_name; + char* * name; + uint8_t pose_length; + geometry_msgs::Pose st_pose; + geometry_msgs::Pose * pose; + uint8_t twist_length; + geometry_msgs::Twist st_twist; + geometry_msgs::Twist * twist; + + LinkStates(): + name_length(0), name(NULL), + pose_length(0), pose(NULL), + twist_length(0), twist(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = pose_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->pose[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = twist_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t pose_lengthT = *(inbuffer + offset++); + if(pose_lengthT > pose_length) + this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + pose_length = pose_lengthT; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->st_pose.deserialize(inbuffer + offset); + memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); + } + uint8_t twist_lengthT = *(inbuffer + offset++); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + twist_length = twist_lengthT; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/LinkStates"; }; + const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ModelState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_gazebo_msgs_ModelState_h +#define _ROS_gazebo_msgs_ModelState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + + class ModelState : public ros::Msg + { + public: + const char* model_name; + geometry_msgs::Pose pose; + geometry_msgs::Twist twist; + const char* reference_frame; + + ModelState(): + model_name(""), + pose(), + twist(), + reference_frame("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + offset += this->pose.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + uint32_t length_reference_frame = strlen(this->reference_frame); + memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); + offset += length_reference_frame; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + uint32_t length_reference_frame; + memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame-1]=0; + this->reference_frame = (char *)(inbuffer + offset-1); + offset += length_reference_frame; + return offset; + } + + const char * getType(){ return "gazebo_msgs/ModelState"; }; + const char * getMD5(){ return "9330fd35f2fcd82d457e54bd54e10593"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ModelStates.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_gazebo_msgs_ModelStates_h +#define _ROS_gazebo_msgs_ModelStates_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" + +namespace gazebo_msgs +{ + + class ModelStates : public ros::Msg + { + public: + uint8_t name_length; + char* st_name; + char* * name; + uint8_t pose_length; + geometry_msgs::Pose st_pose; + geometry_msgs::Pose * pose; + uint8_t twist_length; + geometry_msgs::Twist st_twist; + geometry_msgs::Twist * twist; + + ModelStates(): + name_length(0), name(NULL), + pose_length(0), pose(NULL), + twist_length(0), twist(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = pose_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->pose[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = twist_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t pose_lengthT = *(inbuffer + offset++); + if(pose_lengthT > pose_length) + this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + pose_length = pose_lengthT; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->st_pose.deserialize(inbuffer + offset); + memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); + } + uint8_t twist_lengthT = *(inbuffer + offset++); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + twist_length = twist_lengthT; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/ModelStates"; }; + const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ODEJointProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,238 @@ +#ifndef _ROS_gazebo_msgs_ODEJointProperties_h +#define _ROS_gazebo_msgs_ODEJointProperties_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + + class ODEJointProperties : public ros::Msg + { + public: + uint8_t damping_length; + float st_damping; + float * damping; + uint8_t hiStop_length; + float st_hiStop; + float * hiStop; + uint8_t loStop_length; + float st_loStop; + float * loStop; + uint8_t erp_length; + float st_erp; + float * erp; + uint8_t cfm_length; + float st_cfm; + float * cfm; + uint8_t stop_erp_length; + float st_stop_erp; + float * stop_erp; + uint8_t stop_cfm_length; + float st_stop_cfm; + float * stop_cfm; + uint8_t fudge_factor_length; + float st_fudge_factor; + float * fudge_factor; + uint8_t fmax_length; + float st_fmax; + float * fmax; + uint8_t vel_length; + float st_vel; + float * vel; + + ODEJointProperties(): + damping_length(0), damping(NULL), + hiStop_length(0), hiStop(NULL), + loStop_length(0), loStop(NULL), + erp_length(0), erp(NULL), + cfm_length(0), cfm(NULL), + stop_erp_length(0), stop_erp(NULL), + stop_cfm_length(0), stop_cfm(NULL), + fudge_factor_length(0), fudge_factor(NULL), + fmax_length(0), fmax(NULL), + vel_length(0), vel(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = damping_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < damping_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->damping[i]); + } + *(outbuffer + offset++) = hiStop_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < hiStop_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->hiStop[i]); + } + *(outbuffer + offset++) = loStop_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < loStop_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->loStop[i]); + } + *(outbuffer + offset++) = erp_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < erp_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->erp[i]); + } + *(outbuffer + offset++) = cfm_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < cfm_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->cfm[i]); + } + *(outbuffer + offset++) = stop_erp_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < stop_erp_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->stop_erp[i]); + } + *(outbuffer + offset++) = stop_cfm_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < stop_cfm_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->stop_cfm[i]); + } + *(outbuffer + offset++) = fudge_factor_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fudge_factor_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->fudge_factor[i]); + } + *(outbuffer + offset++) = fmax_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fmax_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->fmax[i]); + } + *(outbuffer + offset++) = vel_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < vel_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->vel[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t damping_lengthT = *(inbuffer + offset++); + if(damping_lengthT > damping_length) + this->damping = (float*)realloc(this->damping, damping_lengthT * sizeof(float)); + offset += 3; + damping_length = damping_lengthT; + for( uint8_t i = 0; i < damping_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_damping)); + memcpy( &(this->damping[i]), &(this->st_damping), sizeof(float)); + } + uint8_t hiStop_lengthT = *(inbuffer + offset++); + if(hiStop_lengthT > hiStop_length) + this->hiStop = (float*)realloc(this->hiStop, hiStop_lengthT * sizeof(float)); + offset += 3; + hiStop_length = hiStop_lengthT; + for( uint8_t i = 0; i < hiStop_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_hiStop)); + memcpy( &(this->hiStop[i]), &(this->st_hiStop), sizeof(float)); + } + uint8_t loStop_lengthT = *(inbuffer + offset++); + if(loStop_lengthT > loStop_length) + this->loStop = (float*)realloc(this->loStop, loStop_lengthT * sizeof(float)); + offset += 3; + loStop_length = loStop_lengthT; + for( uint8_t i = 0; i < loStop_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_loStop)); + memcpy( &(this->loStop[i]), &(this->st_loStop), sizeof(float)); + } + uint8_t erp_lengthT = *(inbuffer + offset++); + if(erp_lengthT > erp_length) + this->erp = (float*)realloc(this->erp, erp_lengthT * sizeof(float)); + offset += 3; + erp_length = erp_lengthT; + for( uint8_t i = 0; i < erp_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_erp)); + memcpy( &(this->erp[i]), &(this->st_erp), sizeof(float)); + } + uint8_t cfm_lengthT = *(inbuffer + offset++); + if(cfm_lengthT > cfm_length) + this->cfm = (float*)realloc(this->cfm, cfm_lengthT * sizeof(float)); + offset += 3; + cfm_length = cfm_lengthT; + for( uint8_t i = 0; i < cfm_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_cfm)); + memcpy( &(this->cfm[i]), &(this->st_cfm), sizeof(float)); + } + uint8_t stop_erp_lengthT = *(inbuffer + offset++); + if(stop_erp_lengthT > stop_erp_length) + this->stop_erp = (float*)realloc(this->stop_erp, stop_erp_lengthT * sizeof(float)); + offset += 3; + stop_erp_length = stop_erp_lengthT; + for( uint8_t i = 0; i < stop_erp_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_stop_erp)); + memcpy( &(this->stop_erp[i]), &(this->st_stop_erp), sizeof(float)); + } + uint8_t stop_cfm_lengthT = *(inbuffer + offset++); + if(stop_cfm_lengthT > stop_cfm_length) + this->stop_cfm = (float*)realloc(this->stop_cfm, stop_cfm_lengthT * sizeof(float)); + offset += 3; + stop_cfm_length = stop_cfm_lengthT; + for( uint8_t i = 0; i < stop_cfm_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_stop_cfm)); + memcpy( &(this->stop_cfm[i]), &(this->st_stop_cfm), sizeof(float)); + } + uint8_t fudge_factor_lengthT = *(inbuffer + offset++); + if(fudge_factor_lengthT > fudge_factor_length) + this->fudge_factor = (float*)realloc(this->fudge_factor, fudge_factor_lengthT * sizeof(float)); + offset += 3; + fudge_factor_length = fudge_factor_lengthT; + for( uint8_t i = 0; i < fudge_factor_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_fudge_factor)); + memcpy( &(this->fudge_factor[i]), &(this->st_fudge_factor), sizeof(float)); + } + uint8_t fmax_lengthT = *(inbuffer + offset++); + if(fmax_lengthT > fmax_length) + this->fmax = (float*)realloc(this->fmax, fmax_lengthT * sizeof(float)); + offset += 3; + fmax_length = fmax_lengthT; + for( uint8_t i = 0; i < fmax_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_fmax)); + memcpy( &(this->fmax[i]), &(this->st_fmax), sizeof(float)); + } + uint8_t vel_lengthT = *(inbuffer + offset++); + if(vel_lengthT > vel_length) + this->vel = (float*)realloc(this->vel, vel_lengthT * sizeof(float)); + offset += 3; + vel_length = vel_lengthT; + for( uint8_t i = 0; i < vel_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_vel)); + memcpy( &(this->vel[i]), &(this->st_vel), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/ODEJointProperties"; }; + const char * getMD5(){ return "1b744c32a920af979f53afe2f9c3511f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/ODEPhysics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,115 @@ +#ifndef _ROS_gazebo_msgs_ODEPhysics_h +#define _ROS_gazebo_msgs_ODEPhysics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + + class ODEPhysics : public ros::Msg + { + public: + bool auto_disable_bodies; + uint32_t sor_pgs_precon_iters; + uint32_t sor_pgs_iters; + float sor_pgs_w; + float sor_pgs_rms_error_tol; + float contact_surface_layer; + float contact_max_correcting_vel; + float cfm; + float erp; + uint32_t max_contacts; + + ODEPhysics(): + auto_disable_bodies(0), + sor_pgs_precon_iters(0), + sor_pgs_iters(0), + sor_pgs_w(0), + sor_pgs_rms_error_tol(0), + contact_surface_layer(0), + contact_max_correcting_vel(0), + cfm(0), + erp(0), + max_contacts(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_auto_disable_bodies; + u_auto_disable_bodies.real = this->auto_disable_bodies; + *(outbuffer + offset + 0) = (u_auto_disable_bodies.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->auto_disable_bodies); + *(outbuffer + offset + 0) = (this->sor_pgs_precon_iters >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->sor_pgs_precon_iters >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->sor_pgs_precon_iters >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->sor_pgs_precon_iters >> (8 * 3)) & 0xFF; + offset += sizeof(this->sor_pgs_precon_iters); + *(outbuffer + offset + 0) = (this->sor_pgs_iters >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->sor_pgs_iters >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->sor_pgs_iters >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->sor_pgs_iters >> (8 * 3)) & 0xFF; + offset += sizeof(this->sor_pgs_iters); + offset += serializeAvrFloat64(outbuffer + offset, this->sor_pgs_w); + offset += serializeAvrFloat64(outbuffer + offset, this->sor_pgs_rms_error_tol); + offset += serializeAvrFloat64(outbuffer + offset, this->contact_surface_layer); + offset += serializeAvrFloat64(outbuffer + offset, this->contact_max_correcting_vel); + offset += serializeAvrFloat64(outbuffer + offset, this->cfm); + offset += serializeAvrFloat64(outbuffer + offset, this->erp); + *(outbuffer + offset + 0) = (this->max_contacts >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->max_contacts >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->max_contacts >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->max_contacts >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_contacts); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_auto_disable_bodies; + u_auto_disable_bodies.base = 0; + u_auto_disable_bodies.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->auto_disable_bodies = u_auto_disable_bodies.real; + offset += sizeof(this->auto_disable_bodies); + this->sor_pgs_precon_iters = ((uint32_t) (*(inbuffer + offset))); + this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->sor_pgs_precon_iters |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->sor_pgs_precon_iters); + this->sor_pgs_iters = ((uint32_t) (*(inbuffer + offset))); + this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->sor_pgs_iters |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->sor_pgs_iters); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->sor_pgs_w)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->sor_pgs_rms_error_tol)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->contact_surface_layer)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->contact_max_correcting_vel)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->cfm)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->erp)); + this->max_contacts = ((uint32_t) (*(inbuffer + offset))); + this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->max_contacts |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->max_contacts); + return offset; + } + + const char * getType(){ return "gazebo_msgs/ODEPhysics"; }; + const char * getMD5(){ return "667d56ddbd547918c32d1934503dc335"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetJointProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,125 @@ +#ifndef _ROS_SERVICE_SetJointProperties_h +#define _ROS_SERVICE_SetJointProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "gazebo_msgs/ODEJointProperties.h" + +namespace gazebo_msgs +{ + +static const char SETJOINTPROPERTIES[] = "gazebo_msgs/SetJointProperties"; + + class SetJointPropertiesRequest : public ros::Msg + { + public: + const char* joint_name; + gazebo_msgs::ODEJointProperties ode_joint_config; + + SetJointPropertiesRequest(): + joint_name(""), + ode_joint_config() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + offset += this->ode_joint_config.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + offset += this->ode_joint_config.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETJOINTPROPERTIES; }; + const char * getMD5(){ return "331fd8f35fd27e3c1421175590258e26"; }; + + }; + + class SetJointPropertiesResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetJointPropertiesResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETJOINTPROPERTIES; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetJointProperties { + public: + typedef SetJointPropertiesRequest Request; + typedef SetJointPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetJointTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,164 @@ +#ifndef _ROS_SERVICE_SetJointTrajectory_h +#define _ROS_SERVICE_SetJointTrajectory_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "geometry_msgs/Pose.h" + +namespace gazebo_msgs +{ + +static const char SETJOINTTRAJECTORY[] = "gazebo_msgs/SetJointTrajectory"; + + class SetJointTrajectoryRequest : public ros::Msg + { + public: + const char* model_name; + trajectory_msgs::JointTrajectory joint_trajectory; + geometry_msgs::Pose model_pose; + bool set_model_pose; + bool disable_physics_updates; + + SetJointTrajectoryRequest(): + model_name(""), + joint_trajectory(), + model_pose(), + set_model_pose(0), + disable_physics_updates(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + offset += this->joint_trajectory.serialize(outbuffer + offset); + offset += this->model_pose.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_set_model_pose; + u_set_model_pose.real = this->set_model_pose; + *(outbuffer + offset + 0) = (u_set_model_pose.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->set_model_pose); + union { + bool real; + uint8_t base; + } u_disable_physics_updates; + u_disable_physics_updates.real = this->disable_physics_updates; + *(outbuffer + offset + 0) = (u_disable_physics_updates.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->disable_physics_updates); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + offset += this->joint_trajectory.deserialize(inbuffer + offset); + offset += this->model_pose.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_set_model_pose; + u_set_model_pose.base = 0; + u_set_model_pose.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->set_model_pose = u_set_model_pose.real; + offset += sizeof(this->set_model_pose); + union { + bool real; + uint8_t base; + } u_disable_physics_updates; + u_disable_physics_updates.base = 0; + u_disable_physics_updates.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->disable_physics_updates = u_disable_physics_updates.real; + offset += sizeof(this->disable_physics_updates); + return offset; + } + + const char * getType(){ return SETJOINTTRAJECTORY; }; + const char * getMD5(){ return "649dd2eba5ffd358069238825f9f85ab"; }; + + }; + + class SetJointTrajectoryResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetJointTrajectoryResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETJOINTTRAJECTORY; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetJointTrajectory { + public: + typedef SetJointTrajectoryRequest Request; + typedef SetJointTrajectoryResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetLinkProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,170 @@ +#ifndef _ROS_SERVICE_SetLinkProperties_h +#define _ROS_SERVICE_SetLinkProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" + +namespace gazebo_msgs +{ + +static const char SETLINKPROPERTIES[] = "gazebo_msgs/SetLinkProperties"; + + class SetLinkPropertiesRequest : public ros::Msg + { + public: + const char* link_name; + geometry_msgs::Pose com; + bool gravity_mode; + float mass; + float ixx; + float ixy; + float ixz; + float iyy; + float iyz; + float izz; + + SetLinkPropertiesRequest(): + link_name(""), + com(), + gravity_mode(0), + mass(0), + ixx(0), + ixy(0), + ixz(0), + iyy(0), + iyz(0), + izz(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += this->com.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_gravity_mode; + u_gravity_mode.real = this->gravity_mode; + *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->gravity_mode); + offset += serializeAvrFloat64(outbuffer + offset, this->mass); + offset += serializeAvrFloat64(outbuffer + offset, this->ixx); + offset += serializeAvrFloat64(outbuffer + offset, this->ixy); + offset += serializeAvrFloat64(outbuffer + offset, this->ixz); + offset += serializeAvrFloat64(outbuffer + offset, this->iyy); + offset += serializeAvrFloat64(outbuffer + offset, this->iyz); + offset += serializeAvrFloat64(outbuffer + offset, this->izz); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += this->com.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_gravity_mode; + u_gravity_mode.base = 0; + u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->gravity_mode = u_gravity_mode.real; + offset += sizeof(this->gravity_mode); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->mass)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixx)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixy)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->ixz)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyy)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->iyz)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->izz)); + return offset; + } + + const char * getType(){ return SETLINKPROPERTIES; }; + const char * getMD5(){ return "68ac74a4be01b165bc305b5ccdc45e91"; }; + + }; + + class SetLinkPropertiesResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetLinkPropertiesResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETLINKPROPERTIES; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetLinkProperties { + public: + typedef SetLinkPropertiesRequest Request; + typedef SetLinkPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetLinkState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,109 @@ +#ifndef _ROS_SERVICE_SetLinkState_h +#define _ROS_SERVICE_SetLinkState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "gazebo_msgs/LinkState.h" + +namespace gazebo_msgs +{ + +static const char SETLINKSTATE[] = "gazebo_msgs/SetLinkState"; + + class SetLinkStateRequest : public ros::Msg + { + public: + gazebo_msgs::LinkState link_state; + + SetLinkStateRequest(): + link_state() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->link_state.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->link_state.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETLINKSTATE; }; + const char * getMD5(){ return "22a2c757d56911b6f27868159e9a872d"; }; + + }; + + class SetLinkStateResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetLinkStateResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETLINKSTATE; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetLinkState { + public: + typedef SetLinkStateRequest Request; + typedef SetLinkStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetModelConfiguration.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,188 @@ +#ifndef _ROS_SERVICE_SetModelConfiguration_h +#define _ROS_SERVICE_SetModelConfiguration_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace gazebo_msgs +{ + +static const char SETMODELCONFIGURATION[] = "gazebo_msgs/SetModelConfiguration"; + + class SetModelConfigurationRequest : public ros::Msg + { + public: + const char* model_name; + const char* urdf_param_name; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t joint_positions_length; + float st_joint_positions; + float * joint_positions; + + SetModelConfigurationRequest(): + model_name(""), + urdf_param_name(""), + joint_names_length(0), joint_names(NULL), + joint_positions_length(0), joint_positions(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + uint32_t length_urdf_param_name = strlen(this->urdf_param_name); + memcpy(outbuffer + offset, &length_urdf_param_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->urdf_param_name, length_urdf_param_name); + offset += length_urdf_param_name; + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = joint_positions_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_positions_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->joint_positions[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + uint32_t length_urdf_param_name; + memcpy(&length_urdf_param_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_urdf_param_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_urdf_param_name-1]=0; + this->urdf_param_name = (char *)(inbuffer + offset-1); + offset += length_urdf_param_name; + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t joint_positions_lengthT = *(inbuffer + offset++); + if(joint_positions_lengthT > joint_positions_length) + this->joint_positions = (float*)realloc(this->joint_positions, joint_positions_lengthT * sizeof(float)); + offset += 3; + joint_positions_length = joint_positions_lengthT; + for( uint8_t i = 0; i < joint_positions_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_joint_positions)); + memcpy( &(this->joint_positions[i]), &(this->st_joint_positions), sizeof(float)); + } + return offset; + } + + const char * getType(){ return SETMODELCONFIGURATION; }; + const char * getMD5(){ return "160eae60f51fabff255480c70afa289f"; }; + + }; + + class SetModelConfigurationResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetModelConfigurationResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETMODELCONFIGURATION; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetModelConfiguration { + public: + typedef SetModelConfigurationRequest Request; + typedef SetModelConfigurationResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetModelState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,109 @@ +#ifndef _ROS_SERVICE_SetModelState_h +#define _ROS_SERVICE_SetModelState_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "gazebo_msgs/ModelState.h" + +namespace gazebo_msgs +{ + +static const char SETMODELSTATE[] = "gazebo_msgs/SetModelState"; + + class SetModelStateRequest : public ros::Msg + { + public: + gazebo_msgs::ModelState model_state; + + SetModelStateRequest(): + model_state() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->model_state.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->model_state.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETMODELSTATE; }; + const char * getMD5(){ return "cb042b0e91880f4661b29ea5b6234350"; }; + + }; + + class SetModelStateResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetModelStateResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETMODELSTATE; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetModelState { + public: + typedef SetModelStateRequest Request; + typedef SetModelStateResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SetPhysicsProperties.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,122 @@ +#ifndef _ROS_SERVICE_SetPhysicsProperties_h +#define _ROS_SERVICE_SetPhysicsProperties_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" +#include "gazebo_msgs/ODEPhysics.h" + +namespace gazebo_msgs +{ + +static const char SETPHYSICSPROPERTIES[] = "gazebo_msgs/SetPhysicsProperties"; + + class SetPhysicsPropertiesRequest : public ros::Msg + { + public: + float time_step; + float max_update_rate; + geometry_msgs::Vector3 gravity; + gazebo_msgs::ODEPhysics ode_config; + + SetPhysicsPropertiesRequest(): + time_step(0), + max_update_rate(0), + gravity(), + ode_config() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->time_step); + offset += serializeAvrFloat64(outbuffer + offset, this->max_update_rate); + offset += this->gravity.serialize(outbuffer + offset); + offset += this->ode_config.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->time_step)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_update_rate)); + offset += this->gravity.deserialize(inbuffer + offset); + offset += this->ode_config.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETPHYSICSPROPERTIES; }; + const char * getMD5(){ return "abd9f82732b52b92e9d6bb36e6a82452"; }; + + }; + + class SetPhysicsPropertiesResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SetPhysicsPropertiesResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETPHYSICSPROPERTIES; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetPhysicsProperties { + public: + typedef SetPhysicsPropertiesRequest Request; + typedef SetPhysicsPropertiesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/SpawnModel.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,173 @@ +#ifndef _ROS_SERVICE_SpawnModel_h +#define _ROS_SERVICE_SpawnModel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" + +namespace gazebo_msgs +{ + +static const char SPAWNMODEL[] = "gazebo_msgs/SpawnModel"; + + class SpawnModelRequest : public ros::Msg + { + public: + const char* model_name; + const char* model_xml; + const char* robot_namespace; + geometry_msgs::Pose initial_pose; + const char* reference_frame; + + SpawnModelRequest(): + model_name(""), + model_xml(""), + robot_namespace(""), + initial_pose(), + reference_frame("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_name = strlen(this->model_name); + memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_name, length_model_name); + offset += length_model_name; + uint32_t length_model_xml = strlen(this->model_xml); + memcpy(outbuffer + offset, &length_model_xml, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_xml, length_model_xml); + offset += length_model_xml; + uint32_t length_robot_namespace = strlen(this->robot_namespace); + memcpy(outbuffer + offset, &length_robot_namespace, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->robot_namespace, length_robot_namespace); + offset += length_robot_namespace; + offset += this->initial_pose.serialize(outbuffer + offset); + uint32_t length_reference_frame = strlen(this->reference_frame); + memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); + offset += length_reference_frame; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_name; + memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_name-1]=0; + this->model_name = (char *)(inbuffer + offset-1); + offset += length_model_name; + uint32_t length_model_xml; + memcpy(&length_model_xml, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_xml; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_xml-1]=0; + this->model_xml = (char *)(inbuffer + offset-1); + offset += length_model_xml; + uint32_t length_robot_namespace; + memcpy(&length_robot_namespace, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_robot_namespace; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_robot_namespace-1]=0; + this->robot_namespace = (char *)(inbuffer + offset-1); + offset += length_robot_namespace; + offset += this->initial_pose.deserialize(inbuffer + offset); + uint32_t length_reference_frame; + memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame-1]=0; + this->reference_frame = (char *)(inbuffer + offset-1); + offset += length_reference_frame; + return offset; + } + + const char * getType(){ return SPAWNMODEL; }; + const char * getMD5(){ return "6d0eba5753761cd57e6263a056b79930"; }; + + }; + + class SpawnModelResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + + SpawnModelResponse(): + success(0), + status_message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SPAWNMODEL; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SpawnModel { + public: + typedef SpawnModelRequest Request; + typedef SpawnModelResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/gazebo_msgs/WorldState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_gazebo_msgs_WorldState_h +#define _ROS_gazebo_msgs_WorldState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Twist.h" +#include "geometry_msgs/Wrench.h" + +namespace gazebo_msgs +{ + + class WorldState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t name_length; + char* st_name; + char* * name; + uint8_t pose_length; + geometry_msgs::Pose st_pose; + geometry_msgs::Pose * pose; + uint8_t twist_length; + geometry_msgs::Twist st_twist; + geometry_msgs::Twist * twist; + uint8_t wrench_length; + geometry_msgs::Wrench st_wrench; + geometry_msgs::Wrench * wrench; + + WorldState(): + header(), + name_length(0), name(NULL), + pose_length(0), pose(NULL), + twist_length(0), twist(NULL), + wrench_length(0), wrench(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen(this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = pose_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->pose[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = twist_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = wrench_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < wrench_length; i++){ + offset += this->wrench[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t pose_lengthT = *(inbuffer + offset++); + if(pose_lengthT > pose_length) + this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + pose_length = pose_lengthT; + for( uint8_t i = 0; i < pose_length; i++){ + offset += this->st_pose.deserialize(inbuffer + offset); + memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); + } + uint8_t twist_lengthT = *(inbuffer + offset++); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + twist_length = twist_lengthT; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + uint8_t wrench_lengthT = *(inbuffer + offset++); + if(wrench_lengthT > wrench_length) + this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench)); + offset += 3; + wrench_length = wrench_lengthT; + for( uint8_t i = 0; i < wrench_length; i++){ + offset += this->st_wrench.deserialize(inbuffer + offset); + memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench)); + } + return offset; + } + + const char * getType(){ return "gazebo_msgs/WorldState"; }; + const char * getMD5(){ return "de1a9de3ab7ba97ac0e9ec01a4eb481e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Point.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_geometry_msgs_Point_h +#define _ROS_geometry_msgs_Point_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Point : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (long *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (long *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (long *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Point"; }; + virtual const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Point32.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,100 @@ +#ifndef _ROS_geometry_msgs_Point32_h +#define _ROS_geometry_msgs_Point32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Point32 : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_z; + u_z.real = this->z; + *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_z; + u_z.base = 0; + u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->z = u_z.real; + offset += sizeof(this->z); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Point32"; }; + virtual const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PointStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PointStamped_h +#define _ROS_geometry_msgs_PointStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" + +namespace geometry_msgs +{ + + class PointStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Point point; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->point.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->point.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/PointStamped"; }; + virtual const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Polygon.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_geometry_msgs_Polygon_h +#define _ROS_geometry_msgs_Polygon_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Point32.h" + +namespace geometry_msgs +{ + + class Polygon : public ros::Msg + { + public: + uint8_t points_length; + geometry_msgs::Point32 st_points; + geometry_msgs::Point32 * points; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); + } + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Polygon"; }; + virtual const char * getMD5(){ return "cd60a26494a087f577976f0329fa120e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PolygonStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_geometry_msgs_PolygonStamped_h +#define _ROS_geometry_msgs_PolygonStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Polygon.h" + +namespace geometry_msgs +{ + + class PolygonStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Polygon polygon; + + PolygonStamped(): + header(), + polygon() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->polygon.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->polygon.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/PolygonStamped"; }; + const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Pose.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Pose_h +#define _ROS_geometry_msgs_Pose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Point.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class Pose : public ros::Msg + { + public: + geometry_msgs::Point position; + geometry_msgs::Quaternion orientation; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->position.serialize(outbuffer + offset); + offset += this->orientation.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->position.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Pose"; }; + virtual const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Pose2D.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_geometry_msgs_Pose2D_h +#define _ROS_geometry_msgs_Pose2D_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Pose2D : public ros::Msg + { + public: + float x; + float y; + float theta; + + Pose2D(): + x(0), + y(0), + theta(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->x); + offset += serializeAvrFloat64(outbuffer + offset, this->y); + offset += serializeAvrFloat64(outbuffer + offset, this->theta); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->theta)); + return offset; + } + + const char * getType(){ return "geometry_msgs/Pose2D"; }; + const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_geometry_msgs_PoseArray_h +#define _ROS_geometry_msgs_PoseArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t poses_length; + geometry_msgs::Pose st_poses; + geometry_msgs::Pose * poses; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->poses[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t poses_lengthT = *(inbuffer + offset++); + if(poses_lengthT > poses_length) + this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + poses_length = poses_lengthT; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->st_poses.deserialize(inbuffer + offset); + memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose)); + } + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/PoseArray"; }; + virtual const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PoseStamped_h +#define _ROS_geometry_msgs_PoseStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose pose; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/PoseStamped"; }; + virtual const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseWithCovariance.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_geometry_msgs_PoseWithCovariance_h +#define _ROS_geometry_msgs_PoseWithCovariance_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseWithCovariance : public ros::Msg + { + public: + geometry_msgs::Pose pose; + float covariance[36]; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->pose.serialize(outbuffer + offset); + unsigned char * covariance_val = (unsigned char *) this->covariance; + for( uint8_t i = 0; i < 36; i++){ + int32_t * val_covariancei = (long *) &(this->covariance[i]); + int32_t exp_covariancei = (((*val_covariancei)>>23)&255); + if(exp_covariancei != 0) + exp_covariancei += 1023-127; + int32_t sig_covariancei = *val_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F; + if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->pose.deserialize(inbuffer + offset); + uint8_t * covariance_val = (uint8_t*) this->covariance; + for( uint8_t i = 0; i < 36; i++){ + uint32_t * val_covariancei = (uint32_t*) &(this->covariance[i]); + offset += 3; + *val_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_covariancei !=0) + *val_covariancei |= ((exp_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i]; + } + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/PoseWithCovariance"; }; + virtual const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseWithCovarianceStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h +#define _ROS_geometry_msgs_PoseWithCovarianceStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseWithCovariance.h" + +namespace geometry_msgs +{ + + class PoseWithCovarianceStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::PoseWithCovariance pose; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; }; + virtual const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Quaternion.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_geometry_msgs_Quaternion_h +#define _ROS_geometry_msgs_Quaternion_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Quaternion : public ros::Msg + { + public: + float x; + float y; + float z; + float w; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (long *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (long *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (long *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_w = (long *) &(this->w); + int32_t exp_w = (((*val_w)>>23)&255); + if(exp_w != 0) + exp_w += 1023-127; + int32_t sig_w = *val_w; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_w<<5) & 0xff; + *(outbuffer + offset++) = (sig_w>>3) & 0xff; + *(outbuffer + offset++) = (sig_w>>11) & 0xff; + *(outbuffer + offset++) = ((exp_w<<4) & 0xF0) | ((sig_w>>19)&0x0F); + *(outbuffer + offset++) = (exp_w>>4) & 0x7F; + if(this->w < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + uint32_t * val_w = (uint32_t*) &(this->w); + offset += 3; + *val_w = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_w |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_w = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_w |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_w !=0) + *val_w |= ((exp_w)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->w = -this->w; + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Quaternion"; }; + virtual const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/QuaternionStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_QuaternionStamped_h +#define _ROS_geometry_msgs_QuaternionStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class QuaternionStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Quaternion quaternion; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->quaternion.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->quaternion.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/QuaternionStamped"; }; + virtual const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Transform.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Transform_h +#define _ROS_geometry_msgs_Transform_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class Transform : public ros::Msg + { + public: + geometry_msgs::Vector3 translation; + geometry_msgs::Quaternion rotation; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->translation.serialize(outbuffer + offset); + offset += this->rotation.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->translation.deserialize(inbuffer + offset); + offset += this->rotation.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Transform"; }; + virtual const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TransformStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_geometry_msgs_TransformStamped_h +#define _ROS_geometry_msgs_TransformStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Transform.h" + +namespace geometry_msgs +{ + + class TransformStamped : public ros::Msg + { + public: + std_msgs::Header header; + char * child_frame_id; + geometry_msgs::Transform transform; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t * length_child_frame_id = (uint32_t *)(outbuffer + offset); + *length_child_frame_id = strlen( (const char*) this->child_frame_id); + offset += 4; + memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id); + offset += *length_child_frame_id; + offset += this->transform.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_child_frame_id = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_child_frame_id-1]=0; + this->child_frame_id = (char *)(inbuffer + offset-1); + offset += length_child_frame_id; + offset += this->transform.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/TransformStamped"; }; + virtual const char * getMD5(){ return "b5764a33bfeb3588febc2682852579b0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Twist.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_geometry_msgs_Twist_h +#define _ROS_geometry_msgs_Twist_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Twist : public ros::Msg + { + public: + geometry_msgs::Vector3 linear; + geometry_msgs::Vector3 angular; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->linear.serialize(outbuffer + offset); + offset += this->angular.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->linear.deserialize(inbuffer + offset); + offset += this->angular.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Twist"; }; + virtual const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_TwistStamped_h +#define _ROS_geometry_msgs_TwistStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Twist.h" + +namespace geometry_msgs +{ + + class TwistStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Twist twist; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/TwistStamped"; }; + virtual const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistWithCovariance.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,21 @@ +#ifndef _ROS_geometry_msgs_TwistWithCovariance_h +#define _ROS_geometry_msgs_TwistWithCovariance_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Twist.h" + +namespace geometry_msgs +{ + + class TwistWithCovariance : public ros::Msg + { + public: + geometry_msgs::Twist twist; + float covariance[36]; + + TwistWithCovariance(): + twist(), +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistWithCovarianceStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h +#define _ROS_geometry_msgs_TwistWithCovarianceStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/TwistWithCovariance.h" + +namespace geometry_msgs +{ + + class TwistWithCovarianceStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::TwistWithCovariance twist; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; }; + virtual const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Vector3.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_geometry_msgs_Vector3_h +#define _ROS_geometry_msgs_Vector3_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Vector3 : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (long *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (long *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (long *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Vector3"; }; + virtual const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Vector3Stamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Vector3Stamped_h +#define _ROS_geometry_msgs_Vector3Stamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Vector3Stamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Vector3 vector; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->vector.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->vector.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Vector3Stamped"; }; + virtual const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Wrench.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_geometry_msgs_Wrench_h +#define _ROS_geometry_msgs_Wrench_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Wrench : public ros::Msg + { + public: + geometry_msgs::Vector3 force; + geometry_msgs::Vector3 torque; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->force.serialize(outbuffer + offset); + offset += this->torque.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->force.deserialize(inbuffer + offset); + offset += this->torque.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/Wrench"; }; + virtual const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/WrenchStamped.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_WrenchStamped_h +#define _ROS_geometry_msgs_WrenchStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Wrench.h" + +namespace geometry_msgs +{ + + class WrenchStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Wrench wrench; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->wrench.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->wrench.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return "geometry_msgs/WrenchStamped"; }; + virtual const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/DatabaseModelPose.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,110 @@ +#ifndef _ROS_household_objects_database_msgs_DatabaseModelPose_h +#define _ROS_household_objects_database_msgs_DatabaseModelPose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "object_recognition_msgs/ObjectType.h" +#include "geometry_msgs/PoseStamped.h" + +namespace household_objects_database_msgs +{ + + class DatabaseModelPose : public ros::Msg + { + public: + int32_t model_id; + object_recognition_msgs::ObjectType type; + geometry_msgs::PoseStamped pose; + float confidence; + const char* detector_name; + + DatabaseModelPose(): + model_id(0), + type(), + pose(), + confidence(0), + detector_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.real = this->model_id; + *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_id); + offset += this->type.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_confidence; + u_confidence.real = this->confidence; + *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->confidence); + uint32_t length_detector_name = strlen(this->detector_name); + memcpy(outbuffer + offset, &length_detector_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->detector_name, length_detector_name); + offset += length_detector_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.base = 0; + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->model_id = u_model_id.real; + offset += sizeof(this->model_id); + offset += this->type.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_confidence; + u_confidence.base = 0; + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->confidence = u_confidence.real; + offset += sizeof(this->confidence); + uint32_t length_detector_name; + memcpy(&length_detector_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_detector_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_detector_name-1]=0; + this->detector_name = (char *)(inbuffer + offset-1); + offset += length_detector_name; + return offset; + } + + const char * getType(){ return "household_objects_database_msgs/DatabaseModelPose"; }; + const char * getMD5(){ return "6bc39ef48ca57cc7d4341cfc13a5a110"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/DatabaseModelPoseList.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_household_objects_database_msgs_DatabaseModelPoseList_h +#define _ROS_household_objects_database_msgs_DatabaseModelPoseList_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseModelPose.h" + +namespace household_objects_database_msgs +{ + + class DatabaseModelPoseList : public ros::Msg + { + public: + uint8_t model_list_length; + household_objects_database_msgs::DatabaseModelPose st_model_list; + household_objects_database_msgs::DatabaseModelPose * model_list; + + DatabaseModelPoseList(): + model_list_length(0), model_list(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = model_list_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < model_list_length; i++){ + offset += this->model_list[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t model_list_lengthT = *(inbuffer + offset++); + if(model_list_lengthT > model_list_length) + this->model_list = (household_objects_database_msgs::DatabaseModelPose*)realloc(this->model_list, model_list_lengthT * sizeof(household_objects_database_msgs::DatabaseModelPose)); + offset += 3; + model_list_length = model_list_lengthT; + for( uint8_t i = 0; i < model_list_length; i++){ + offset += this->st_model_list.deserialize(inbuffer + offset); + memcpy( &(this->model_list[i]), &(this->st_model_list), sizeof(household_objects_database_msgs::DatabaseModelPose)); + } + return offset; + } + + const char * getType(){ return "household_objects_database_msgs/DatabaseModelPoseList"; }; + const char * getMD5(){ return "f0bb2aa8d2ededee0ffe0f5d2107e099"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/DatabaseReturnCode.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_household_objects_database_msgs_DatabaseReturnCode_h +#define _ROS_household_objects_database_msgs_DatabaseReturnCode_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace household_objects_database_msgs +{ + + class DatabaseReturnCode : public ros::Msg + { + public: + int32_t code; + enum { UNKNOWN_ERROR = 1 }; + enum { DATABASE_NOT_CONNECTED = 2 }; + enum { DATABASE_QUERY_ERROR = 3 }; + enum { SUCCESS = -1 }; + + DatabaseReturnCode(): + code(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_code; + u_code.real = this->code; + *(outbuffer + offset + 0) = (u_code.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_code.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_code.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_code.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->code); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_code; + u_code.base = 0; + u_code.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_code.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_code.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_code.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->code = u_code.real; + offset += sizeof(this->code); + return offset; + } + + const char * getType(){ return "household_objects_database_msgs/DatabaseReturnCode"; }; + const char * getMD5(){ return "b649fd6fa3a4e3bf8e3f4b4e648fa0f1"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/DatabaseScan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,114 @@ +#ifndef _ROS_household_objects_database_msgs_DatabaseScan_h +#define _ROS_household_objects_database_msgs_DatabaseScan_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" + +namespace household_objects_database_msgs +{ + + class DatabaseScan : public ros::Msg + { + public: + int32_t model_id; + const char* bagfile_location; + const char* scan_source; + geometry_msgs::PoseStamped pose; + const char* cloud_topic; + + DatabaseScan(): + model_id(0), + bagfile_location(""), + scan_source(""), + pose(), + cloud_topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.real = this->model_id; + *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_id); + uint32_t length_bagfile_location = strlen(this->bagfile_location); + memcpy(outbuffer + offset, &length_bagfile_location, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->bagfile_location, length_bagfile_location); + offset += length_bagfile_location; + uint32_t length_scan_source = strlen(this->scan_source); + memcpy(outbuffer + offset, &length_scan_source, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->scan_source, length_scan_source); + offset += length_scan_source; + offset += this->pose.serialize(outbuffer + offset); + uint32_t length_cloud_topic = strlen(this->cloud_topic); + memcpy(outbuffer + offset, &length_cloud_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->cloud_topic, length_cloud_topic); + offset += length_cloud_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.base = 0; + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->model_id = u_model_id.real; + offset += sizeof(this->model_id); + uint32_t length_bagfile_location; + memcpy(&length_bagfile_location, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_bagfile_location; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_bagfile_location-1]=0; + this->bagfile_location = (char *)(inbuffer + offset-1); + offset += length_bagfile_location; + uint32_t length_scan_source; + memcpy(&length_scan_source, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_scan_source; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_scan_source-1]=0; + this->scan_source = (char *)(inbuffer + offset-1); + offset += length_scan_source; + offset += this->pose.deserialize(inbuffer + offset); + uint32_t length_cloud_topic; + memcpy(&length_cloud_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_cloud_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_cloud_topic-1]=0; + this->cloud_topic = (char *)(inbuffer + offset-1); + offset += length_cloud_topic; + return offset; + } + + const char * getType(){ return "household_objects_database_msgs/DatabaseScan"; }; + const char * getMD5(){ return "7edb7abec4973143a801c25c336b4bb1"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/GetModelDescription.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,163 @@ +#ifndef _ROS_SERVICE_GetModelDescription_h +#define _ROS_SERVICE_GetModelDescription_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseReturnCode.h" + +namespace household_objects_database_msgs +{ + +static const char GETMODELDESCRIPTION[] = "household_objects_database_msgs/GetModelDescription"; + + class GetModelDescriptionRequest : public ros::Msg + { + public: + int32_t model_id; + + GetModelDescriptionRequest(): + model_id(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.real = this->model_id; + *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_id); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.base = 0; + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->model_id = u_model_id.real; + offset += sizeof(this->model_id); + return offset; + } + + const char * getType(){ return GETMODELDESCRIPTION; }; + const char * getMD5(){ return "28cb0598daf3b969068a38cd07aaa9f6"; }; + + }; + + class GetModelDescriptionResponse : public ros::Msg + { + public: + household_objects_database_msgs::DatabaseReturnCode return_code; + uint8_t tags_length; + char* st_tags; + char* * tags; + const char* name; + const char* maker; + + GetModelDescriptionResponse(): + return_code(), + tags_length(0), tags(NULL), + name(""), + maker("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->return_code.serialize(outbuffer + offset); + *(outbuffer + offset++) = tags_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tags_length; i++){ + uint32_t length_tagsi = strlen(this->tags[i]); + memcpy(outbuffer + offset, &length_tagsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->tags[i], length_tagsi); + offset += length_tagsi; + } + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_maker = strlen(this->maker); + memcpy(outbuffer + offset, &length_maker, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->maker, length_maker); + offset += length_maker; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->return_code.deserialize(inbuffer + offset); + uint8_t tags_lengthT = *(inbuffer + offset++); + if(tags_lengthT > tags_length) + this->tags = (char**)realloc(this->tags, tags_lengthT * sizeof(char*)); + offset += 3; + tags_length = tags_lengthT; + for( uint8_t i = 0; i < tags_length; i++){ + uint32_t length_st_tags; + memcpy(&length_st_tags, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_tags; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_tags-1]=0; + this->st_tags = (char *)(inbuffer + offset-1); + offset += length_st_tags; + memcpy( &(this->tags[i]), &(this->st_tags), sizeof(char*)); + } + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_maker; + memcpy(&length_maker, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_maker; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_maker-1]=0; + this->maker = (char *)(inbuffer + offset-1); + offset += length_maker; + return offset; + } + + const char * getType(){ return GETMODELDESCRIPTION; }; + const char * getMD5(){ return "e6c55e34b143695104d37ad9b33c72c0"; }; + + }; + + class GetModelDescription { + public: + typedef GetModelDescriptionRequest Request; + typedef GetModelDescriptionResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/GetModelList.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,131 @@ +#ifndef _ROS_SERVICE_GetModelList_h +#define _ROS_SERVICE_GetModelList_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseReturnCode.h" + +namespace household_objects_database_msgs +{ + +static const char GETMODELLIST[] = "household_objects_database_msgs/GetModelList"; + + class GetModelListRequest : public ros::Msg + { + public: + const char* model_set; + + GetModelListRequest(): + model_set("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_set = strlen(this->model_set); + memcpy(outbuffer + offset, &length_model_set, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_set, length_model_set); + offset += length_model_set; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_set; + memcpy(&length_model_set, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_set; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_set-1]=0; + this->model_set = (char *)(inbuffer + offset-1); + offset += length_model_set; + return offset; + } + + const char * getType(){ return GETMODELLIST; }; + const char * getMD5(){ return "6bdf0a866151f41b8876e73800929933"; }; + + }; + + class GetModelListResponse : public ros::Msg + { + public: + household_objects_database_msgs::DatabaseReturnCode return_code; + uint8_t model_ids_length; + int32_t st_model_ids; + int32_t * model_ids; + + GetModelListResponse(): + return_code(), + model_ids_length(0), model_ids(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->return_code.serialize(outbuffer + offset); + *(outbuffer + offset++) = model_ids_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < model_ids_length; i++){ + union { + int32_t real; + uint32_t base; + } u_model_idsi; + u_model_idsi.real = this->model_ids[i]; + *(outbuffer + offset + 0) = (u_model_idsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_idsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_idsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_idsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_ids[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->return_code.deserialize(inbuffer + offset); + uint8_t model_ids_lengthT = *(inbuffer + offset++); + if(model_ids_lengthT > model_ids_length) + this->model_ids = (int32_t*)realloc(this->model_ids, model_ids_lengthT * sizeof(int32_t)); + offset += 3; + model_ids_length = model_ids_lengthT; + for( uint8_t i = 0; i < model_ids_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_model_ids; + u_st_model_ids.base = 0; + u_st_model_ids.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_model_ids.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_model_ids.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_model_ids.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_model_ids = u_st_model_ids.real; + offset += sizeof(this->st_model_ids); + memcpy( &(this->model_ids[i]), &(this->st_model_ids), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return GETMODELLIST; }; + const char * getMD5(){ return "81fac8c5d631e612bd9183a923572d53"; }; + + }; + + class GetModelList { + public: + typedef GetModelListRequest Request; + typedef GetModelListResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/GetModelMesh.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_GetModelMesh_h +#define _ROS_SERVICE_GetModelMesh_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseReturnCode.h" +#include "shape_msgs/Mesh.h" + +namespace household_objects_database_msgs +{ + +static const char GETMODELMESH[] = "household_objects_database_msgs/GetModelMesh"; + + class GetModelMeshRequest : public ros::Msg + { + public: + int32_t model_id; + + GetModelMeshRequest(): + model_id(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.real = this->model_id; + *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_id); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.base = 0; + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->model_id = u_model_id.real; + offset += sizeof(this->model_id); + return offset; + } + + const char * getType(){ return GETMODELMESH; }; + const char * getMD5(){ return "28cb0598daf3b969068a38cd07aaa9f6"; }; + + }; + + class GetModelMeshResponse : public ros::Msg + { + public: + household_objects_database_msgs::DatabaseReturnCode return_code; + shape_msgs::Mesh mesh; + + GetModelMeshResponse(): + return_code(), + mesh() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->return_code.serialize(outbuffer + offset); + offset += this->mesh.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->return_code.deserialize(inbuffer + offset); + offset += this->mesh.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMODELMESH; }; + const char * getMD5(){ return "350330c487efb062c09ffe1ab80683de"; }; + + }; + + class GetModelMesh { + public: + typedef GetModelMeshRequest Request; + typedef GetModelMeshResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/GetModelScans.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,136 @@ +#ifndef _ROS_SERVICE_GetModelScans_h +#define _ROS_SERVICE_GetModelScans_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseReturnCode.h" +#include "household_objects_database_msgs/DatabaseScan.h" + +namespace household_objects_database_msgs +{ + +static const char GETMODELSCANS[] = "household_objects_database_msgs/GetModelScans"; + + class GetModelScansRequest : public ros::Msg + { + public: + int32_t model_id; + const char* scan_source; + + GetModelScansRequest(): + model_id(0), + scan_source("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.real = this->model_id; + *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->model_id); + uint32_t length_scan_source = strlen(this->scan_source); + memcpy(outbuffer + offset, &length_scan_source, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->scan_source, length_scan_source); + offset += length_scan_source; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_model_id; + u_model_id.base = 0; + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->model_id = u_model_id.real; + offset += sizeof(this->model_id); + uint32_t length_scan_source; + memcpy(&length_scan_source, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_scan_source; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_scan_source-1]=0; + this->scan_source = (char *)(inbuffer + offset-1); + offset += length_scan_source; + return offset; + } + + const char * getType(){ return GETMODELSCANS; }; + const char * getMD5(){ return "4f31b0f27ba251f6d1f17eafced83cb7"; }; + + }; + + class GetModelScansResponse : public ros::Msg + { + public: + household_objects_database_msgs::DatabaseReturnCode return_code; + uint8_t matching_scans_length; + household_objects_database_msgs::DatabaseScan st_matching_scans; + household_objects_database_msgs::DatabaseScan * matching_scans; + + GetModelScansResponse(): + return_code(), + matching_scans_length(0), matching_scans(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->return_code.serialize(outbuffer + offset); + *(outbuffer + offset++) = matching_scans_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < matching_scans_length; i++){ + offset += this->matching_scans[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->return_code.deserialize(inbuffer + offset); + uint8_t matching_scans_lengthT = *(inbuffer + offset++); + if(matching_scans_lengthT > matching_scans_length) + this->matching_scans = (household_objects_database_msgs::DatabaseScan*)realloc(this->matching_scans, matching_scans_lengthT * sizeof(household_objects_database_msgs::DatabaseScan)); + offset += 3; + matching_scans_length = matching_scans_lengthT; + for( uint8_t i = 0; i < matching_scans_length; i++){ + offset += this->st_matching_scans.deserialize(inbuffer + offset); + memcpy( &(this->matching_scans[i]), &(this->st_matching_scans), sizeof(household_objects_database_msgs::DatabaseScan)); + } + return offset; + } + + const char * getType(){ return GETMODELSCANS; }; + const char * getMD5(){ return "8d1bb6e95c26a5d891987d9d9195e958"; }; + + }; + + class GetModelScans { + public: + typedef GetModelScansRequest Request; + typedef GetModelScansResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/SaveScan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,152 @@ +#ifndef _ROS_SERVICE_SaveScan_h +#define _ROS_SERVICE_SaveScan_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" +#include "household_objects_database_msgs/DatabaseReturnCode.h" + +namespace household_objects_database_msgs +{ + +static const char SAVESCAN[] = "household_objects_database_msgs/SaveScan"; + + class SaveScanRequest : public ros::Msg + { + public: + int32_t scaled_model_id; + geometry_msgs::PoseStamped ground_truth_pose; + const char* bagfile_location; + const char* scan_source; + const char* cloud_topic; + + SaveScanRequest(): + scaled_model_id(0), + ground_truth_pose(), + bagfile_location(""), + scan_source(""), + cloud_topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_scaled_model_id; + u_scaled_model_id.real = this->scaled_model_id; + *(outbuffer + offset + 0) = (u_scaled_model_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scaled_model_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scaled_model_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scaled_model_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scaled_model_id); + offset += this->ground_truth_pose.serialize(outbuffer + offset); + uint32_t length_bagfile_location = strlen(this->bagfile_location); + memcpy(outbuffer + offset, &length_bagfile_location, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->bagfile_location, length_bagfile_location); + offset += length_bagfile_location; + uint32_t length_scan_source = strlen(this->scan_source); + memcpy(outbuffer + offset, &length_scan_source, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->scan_source, length_scan_source); + offset += length_scan_source; + uint32_t length_cloud_topic = strlen(this->cloud_topic); + memcpy(outbuffer + offset, &length_cloud_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->cloud_topic, length_cloud_topic); + offset += length_cloud_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_scaled_model_id; + u_scaled_model_id.base = 0; + u_scaled_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scaled_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scaled_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scaled_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scaled_model_id = u_scaled_model_id.real; + offset += sizeof(this->scaled_model_id); + offset += this->ground_truth_pose.deserialize(inbuffer + offset); + uint32_t length_bagfile_location; + memcpy(&length_bagfile_location, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_bagfile_location; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_bagfile_location-1]=0; + this->bagfile_location = (char *)(inbuffer + offset-1); + offset += length_bagfile_location; + uint32_t length_scan_source; + memcpy(&length_scan_source, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_scan_source; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_scan_source-1]=0; + this->scan_source = (char *)(inbuffer + offset-1); + offset += length_scan_source; + uint32_t length_cloud_topic; + memcpy(&length_cloud_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_cloud_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_cloud_topic-1]=0; + this->cloud_topic = (char *)(inbuffer + offset-1); + offset += length_cloud_topic; + return offset; + } + + const char * getType(){ return SAVESCAN; }; + const char * getMD5(){ return "492f49d320aa26325df5fb078c297fa5"; }; + + }; + + class SaveScanResponse : public ros::Msg + { + public: + household_objects_database_msgs::DatabaseReturnCode return_code; + + SaveScanResponse(): + return_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->return_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->return_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SAVESCAN; }; + const char * getMD5(){ return "b49fccceeb56b964ed23601916a24082"; }; + + }; + + class SaveScan { + public: + typedef SaveScanRequest Request; + typedef SaveScanResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/household_objects_database_msgs/TranslateRecognitionId.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,203 @@ +#ifndef _ROS_SERVICE_TranslateRecognitionId_h +#define _ROS_SERVICE_TranslateRecognitionId_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace household_objects_database_msgs +{ + +static const char TRANSLATERECOGNITIONID[] = "household_objects_database_msgs/TranslateRecognitionId"; + + class TranslateRecognitionIdRequest : public ros::Msg + { + public: + const char* recognition_id; + + TranslateRecognitionIdRequest(): + recognition_id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_recognition_id = strlen(this->recognition_id); + memcpy(outbuffer + offset, &length_recognition_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->recognition_id, length_recognition_id); + offset += length_recognition_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_recognition_id; + memcpy(&length_recognition_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_recognition_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_recognition_id-1]=0; + this->recognition_id = (char *)(inbuffer + offset-1); + offset += length_recognition_id; + return offset; + } + + const char * getType(){ return TRANSLATERECOGNITIONID; }; + const char * getMD5(){ return "4d95610f63ed69a670a8f8aaa3c6aa36"; }; + + }; + + class TranslateRecognitionIdResponse : public ros::Msg + { + public: + int32_t household_objects_id; + int32_t ID_NOT_FOUND; + int32_t DATABASE_ERROR; + int32_t OTHER_ERROR; + int32_t result; + enum { SUCCESS = 0 }; + + TranslateRecognitionIdResponse(): + household_objects_id(0), + ID_NOT_FOUND(0), + DATABASE_ERROR(0), + OTHER_ERROR(0), + result(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_household_objects_id; + u_household_objects_id.real = this->household_objects_id; + *(outbuffer + offset + 0) = (u_household_objects_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_household_objects_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_household_objects_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_household_objects_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->household_objects_id); + union { + int32_t real; + uint32_t base; + } u_ID_NOT_FOUND; + u_ID_NOT_FOUND.real = this->ID_NOT_FOUND; + *(outbuffer + offset + 0) = (u_ID_NOT_FOUND.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_ID_NOT_FOUND.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_ID_NOT_FOUND.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_ID_NOT_FOUND.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ID_NOT_FOUND); + union { + int32_t real; + uint32_t base; + } u_DATABASE_ERROR; + u_DATABASE_ERROR.real = this->DATABASE_ERROR; + *(outbuffer + offset + 0) = (u_DATABASE_ERROR.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_DATABASE_ERROR.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_DATABASE_ERROR.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_DATABASE_ERROR.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->DATABASE_ERROR); + union { + int32_t real; + uint32_t base; + } u_OTHER_ERROR; + u_OTHER_ERROR.real = this->OTHER_ERROR; + *(outbuffer + offset + 0) = (u_OTHER_ERROR.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_OTHER_ERROR.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_OTHER_ERROR.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_OTHER_ERROR.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->OTHER_ERROR); + 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_household_objects_id; + u_household_objects_id.base = 0; + u_household_objects_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_household_objects_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_household_objects_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_household_objects_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->household_objects_id = u_household_objects_id.real; + offset += sizeof(this->household_objects_id); + union { + int32_t real; + uint32_t base; + } u_ID_NOT_FOUND; + u_ID_NOT_FOUND.base = 0; + u_ID_NOT_FOUND.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_ID_NOT_FOUND.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_ID_NOT_FOUND.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_ID_NOT_FOUND.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->ID_NOT_FOUND = u_ID_NOT_FOUND.real; + offset += sizeof(this->ID_NOT_FOUND); + union { + int32_t real; + uint32_t base; + } u_DATABASE_ERROR; + u_DATABASE_ERROR.base = 0; + u_DATABASE_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_DATABASE_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_DATABASE_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_DATABASE_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->DATABASE_ERROR = u_DATABASE_ERROR.real; + offset += sizeof(this->DATABASE_ERROR); + union { + int32_t real; + uint32_t base; + } u_OTHER_ERROR; + u_OTHER_ERROR.base = 0; + u_OTHER_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_OTHER_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_OTHER_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_OTHER_ERROR.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->OTHER_ERROR = u_OTHER_ERROR.real; + offset += sizeof(this->OTHER_ERROR); + 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 TRANSLATERECOGNITIONID; }; + const char * getMD5(){ return "b4afd505fbee150bf06acaffa82e84cf"; }; + + }; + + class TranslateRecognitionId { + public: + typedef TranslateRecognitionIdRequest Request; + typedef TranslateRecognitionIdResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/CmdJointTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_SERVICE_CmdJointTrajectory_h +#define _ROS_SERVICE_CmdJointTrajectory_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "industrial_msgs/ServiceReturnCode.h" + +namespace industrial_msgs +{ + +static const char CMDJOINTTRAJECTORY[] = "industrial_msgs/CmdJointTrajectory"; + + class CmdJointTrajectoryRequest : public ros::Msg + { + public: + trajectory_msgs::JointTrajectory trajectory; + + CmdJointTrajectoryRequest(): + 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 CMDJOINTTRAJECTORY; }; + const char * getMD5(){ return "2a0eff76c870e8595636c2a562ca298e"; }; + + }; + + class CmdJointTrajectoryResponse : public ros::Msg + { + public: + industrial_msgs::ServiceReturnCode code; + + CmdJointTrajectoryResponse(): + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return CMDJOINTTRAJECTORY; }; + const char * getMD5(){ return "50b1f38f75f5677e5692f3b3e7e1ea48"; }; + + }; + + class CmdJointTrajectory { + public: + typedef CmdJointTrajectoryRequest Request; + typedef CmdJointTrajectoryResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/DebugLevel.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_industrial_msgs_DebugLevel_h +#define _ROS_industrial_msgs_DebugLevel_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace industrial_msgs +{ + + class DebugLevel : public ros::Msg + { + public: + uint8_t val; + enum { DEBUG = 5 }; + enum { INFO = 4 }; + enum { WARN = 3 }; + enum { ERROR = 2 }; + enum { FATAL = 1 }; + enum { NONE = 0 }; + + DebugLevel(): + val(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->val >> (8 * 0)) & 0xFF; + offset += sizeof(this->val); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->val = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->val); + return offset; + } + + const char * getType(){ return "industrial_msgs/DebugLevel"; }; + const char * getMD5(){ return "5bfde194fd95d83abdb02a03ee48fbe7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/DeviceInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,118 @@ +#ifndef _ROS_industrial_msgs_DeviceInfo_h +#define _ROS_industrial_msgs_DeviceInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace industrial_msgs +{ + + class DeviceInfo : public ros::Msg + { + public: + const char* model; + const char* serial_number; + const char* hw_version; + const char* sw_version; + const char* address; + + DeviceInfo(): + model(""), + serial_number(""), + hw_version(""), + sw_version(""), + address("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model = strlen(this->model); + memcpy(outbuffer + offset, &length_model, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model, length_model); + offset += length_model; + uint32_t length_serial_number = strlen(this->serial_number); + memcpy(outbuffer + offset, &length_serial_number, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->serial_number, length_serial_number); + offset += length_serial_number; + uint32_t length_hw_version = strlen(this->hw_version); + memcpy(outbuffer + offset, &length_hw_version, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->hw_version, length_hw_version); + offset += length_hw_version; + uint32_t length_sw_version = strlen(this->sw_version); + memcpy(outbuffer + offset, &length_sw_version, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->sw_version, length_sw_version); + offset += length_sw_version; + uint32_t length_address = strlen(this->address); + memcpy(outbuffer + offset, &length_address, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->address, length_address); + offset += length_address; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model; + memcpy(&length_model, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model-1]=0; + this->model = (char *)(inbuffer + offset-1); + offset += length_model; + uint32_t length_serial_number; + memcpy(&length_serial_number, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_serial_number; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_serial_number-1]=0; + this->serial_number = (char *)(inbuffer + offset-1); + offset += length_serial_number; + uint32_t length_hw_version; + memcpy(&length_hw_version, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_hw_version; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_hw_version-1]=0; + this->hw_version = (char *)(inbuffer + offset-1); + offset += length_hw_version; + uint32_t length_sw_version; + memcpy(&length_sw_version, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_sw_version; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_sw_version-1]=0; + this->sw_version = (char *)(inbuffer + offset-1); + offset += length_sw_version; + uint32_t length_address; + memcpy(&length_address, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_address; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_address-1]=0; + this->address = (char *)(inbuffer + offset-1); + offset += length_address; + return offset; + } + + const char * getType(){ return "industrial_msgs/DeviceInfo"; }; + const char * getMD5(){ return "373ed7fa0fac92d443be9cd5198e80f0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/GetRobotInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,101 @@ +#ifndef _ROS_SERVICE_GetRobotInfo_h +#define _ROS_SERVICE_GetRobotInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "industrial_msgs/ServiceReturnCode.h" +#include "industrial_msgs/DeviceInfo.h" + +namespace industrial_msgs +{ + +static const char GETROBOTINFO[] = "industrial_msgs/GetRobotInfo"; + + class GetRobotInfoRequest : public ros::Msg + { + public: + + GetRobotInfoRequest() + { + } + + 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 GETROBOTINFO; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetRobotInfoResponse : public ros::Msg + { + public: + industrial_msgs::DeviceInfo controller; + uint8_t robots_length; + industrial_msgs::DeviceInfo st_robots; + industrial_msgs::DeviceInfo * robots; + industrial_msgs::ServiceReturnCode code; + + GetRobotInfoResponse(): + controller(), + robots_length(0), robots(NULL), + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->controller.serialize(outbuffer + offset); + *(outbuffer + offset++) = robots_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < robots_length; i++){ + offset += this->robots[i].serialize(outbuffer + offset); + } + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->controller.deserialize(inbuffer + offset); + uint8_t robots_lengthT = *(inbuffer + offset++); + if(robots_lengthT > robots_length) + this->robots = (industrial_msgs::DeviceInfo*)realloc(this->robots, robots_lengthT * sizeof(industrial_msgs::DeviceInfo)); + offset += 3; + robots_length = robots_lengthT; + for( uint8_t i = 0; i < robots_length; i++){ + offset += this->st_robots.deserialize(inbuffer + offset); + memcpy( &(this->robots[i]), &(this->st_robots), sizeof(industrial_msgs::DeviceInfo)); + } + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETROBOTINFO; }; + const char * getMD5(){ return "5db3230b3e61c85a320b999ffd7f3b3f"; }; + + }; + + class GetRobotInfo { + public: + typedef GetRobotInfoRequest Request; + typedef GetRobotInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/RobotMode.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_industrial_msgs_RobotMode_h +#define _ROS_industrial_msgs_RobotMode_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace industrial_msgs +{ + + class RobotMode : public ros::Msg + { + public: + int8_t val; + enum { UNKNOWN = -1 }; + enum { MANUAL = 1 }; + enum { AUTO = 2 }; + + RobotMode(): + val(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.real = this->val; + *(outbuffer + offset + 0) = (u_val.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->val); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.base = 0; + u_val.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->val = u_val.real; + offset += sizeof(this->val); + return offset; + } + + const char * getType(){ return "industrial_msgs/RobotMode"; }; + const char * getMD5(){ return "24ac279e988b6b3db836e437e6ed1ba0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/RobotStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_industrial_msgs_RobotStatus_h +#define _ROS_industrial_msgs_RobotStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "industrial_msgs/RobotMode.h" +#include "industrial_msgs/TriState.h" + +namespace industrial_msgs +{ + + class RobotStatus : public ros::Msg + { + public: + std_msgs::Header header; + industrial_msgs::RobotMode mode; + industrial_msgs::TriState e_stopped; + industrial_msgs::TriState drives_powered; + industrial_msgs::TriState motion_possible; + industrial_msgs::TriState in_motion; + industrial_msgs::TriState in_error; + int32_t error_code; + + RobotStatus(): + header(), + mode(), + e_stopped(), + drives_powered(), + motion_possible(), + in_motion(), + in_error(), + error_code(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->mode.serialize(outbuffer + offset); + offset += this->e_stopped.serialize(outbuffer + offset); + offset += this->drives_powered.serialize(outbuffer + offset); + offset += this->motion_possible.serialize(outbuffer + offset); + offset += this->in_motion.serialize(outbuffer + offset); + offset += this->in_error.serialize(outbuffer + offset); + 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); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->mode.deserialize(inbuffer + offset); + offset += this->e_stopped.deserialize(inbuffer + offset); + offset += this->drives_powered.deserialize(inbuffer + offset); + offset += this->motion_possible.deserialize(inbuffer + offset); + offset += this->in_motion.deserialize(inbuffer + offset); + offset += this->in_error.deserialize(inbuffer + offset); + 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); + return offset; + } + + const char * getType(){ return "industrial_msgs/RobotStatus"; }; + const char * getMD5(){ return "b733cb45a38101840b75c4c0d6093d19"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/ServiceReturnCode.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,57 @@ +#ifndef _ROS_industrial_msgs_ServiceReturnCode_h +#define _ROS_industrial_msgs_ServiceReturnCode_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace industrial_msgs +{ + + class ServiceReturnCode : public ros::Msg + { + public: + int8_t val; + enum { SUCCESS = 1 }; + enum { FAILURE = -1 }; + + ServiceReturnCode(): + val(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.real = this->val; + *(outbuffer + offset + 0) = (u_val.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->val); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.base = 0; + u_val.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->val = u_val.real; + offset += sizeof(this->val); + return offset; + } + + const char * getType(){ return "industrial_msgs/ServiceReturnCode"; }; + const char * getMD5(){ return "85a4e241266be66b1e1426b03083a412"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/SetDrivePower.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,93 @@ +#ifndef _ROS_SERVICE_SetDrivePower_h +#define _ROS_SERVICE_SetDrivePower_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "industrial_msgs/ServiceReturnCode.h" + +namespace industrial_msgs +{ + +static const char SETDRIVEPOWER[] = "industrial_msgs/SetDrivePower"; + + class SetDrivePowerRequest : public ros::Msg + { + public: + bool drive_power; + + SetDrivePowerRequest(): + drive_power(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_drive_power; + u_drive_power.real = this->drive_power; + *(outbuffer + offset + 0) = (u_drive_power.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->drive_power); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_drive_power; + u_drive_power.base = 0; + u_drive_power.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->drive_power = u_drive_power.real; + offset += sizeof(this->drive_power); + return offset; + } + + const char * getType(){ return SETDRIVEPOWER; }; + const char * getMD5(){ return "ad0065fa1febb42851b8c0a0493a1234"; }; + + }; + + class SetDrivePowerResponse : public ros::Msg + { + public: + industrial_msgs::ServiceReturnCode code; + + SetDrivePowerResponse(): + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETDRIVEPOWER; }; + const char * getMD5(){ return "50b1f38f75f5677e5692f3b3e7e1ea48"; }; + + }; + + class SetDrivePower { + public: + typedef SetDrivePowerRequest Request; + typedef SetDrivePowerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/SetRemoteLoggerLevel.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_SERVICE_SetRemoteLoggerLevel_h +#define _ROS_SERVICE_SetRemoteLoggerLevel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "industrial_msgs/ServiceReturnCode.h" +#include "industrial_msgs/DebugLevel.h" + +namespace industrial_msgs +{ + +static const char SETREMOTELOGGERLEVEL[] = "industrial_msgs/SetRemoteLoggerLevel"; + + class SetRemoteLoggerLevelRequest : public ros::Msg + { + public: + industrial_msgs::DebugLevel level; + + SetRemoteLoggerLevelRequest(): + level() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->level.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->level.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETREMOTELOGGERLEVEL; }; + const char * getMD5(){ return "3a0089a136293a269fa1a44788ce9777"; }; + + }; + + class SetRemoteLoggerLevelResponse : public ros::Msg + { + public: + industrial_msgs::ServiceReturnCode code; + + SetRemoteLoggerLevelResponse(): + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETREMOTELOGGERLEVEL; }; + const char * getMD5(){ return "50b1f38f75f5677e5692f3b3e7e1ea48"; }; + + }; + + class SetRemoteLoggerLevel { + public: + typedef SetRemoteLoggerLevelRequest Request; + typedef SetRemoteLoggerLevelResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/StartMotion.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_StartMotion_h +#define _ROS_SERVICE_StartMotion_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "industrial_msgs/ServiceReturnCode.h" + +namespace industrial_msgs +{ + +static const char STARTMOTION[] = "industrial_msgs/StartMotion"; + + class StartMotionRequest : public ros::Msg + { + public: + + StartMotionRequest() + { + } + + 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 STARTMOTION; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class StartMotionResponse : public ros::Msg + { + public: + industrial_msgs::ServiceReturnCode code; + + StartMotionResponse(): + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return STARTMOTION; }; + const char * getMD5(){ return "50b1f38f75f5677e5692f3b3e7e1ea48"; }; + + }; + + class StartMotion { + public: + typedef StartMotionRequest Request; + typedef StartMotionResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/StopMotion.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_StopMotion_h +#define _ROS_SERVICE_StopMotion_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "industrial_msgs/ServiceReturnCode.h" + +namespace industrial_msgs +{ + +static const char STOPMOTION[] = "industrial_msgs/StopMotion"; + + class StopMotionRequest : public ros::Msg + { + public: + + StopMotionRequest() + { + } + + 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 STOPMOTION; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class StopMotionResponse : public ros::Msg + { + public: + industrial_msgs::ServiceReturnCode code; + + StopMotionResponse(): + code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return STOPMOTION; }; + const char * getMD5(){ return "50b1f38f75f5677e5692f3b3e7e1ea48"; }; + + }; + + class StopMotion { + public: + typedef StopMotionRequest Request; + typedef StopMotionResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/industrial_msgs/TriState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,66 @@ +#ifndef _ROS_industrial_msgs_TriState_h +#define _ROS_industrial_msgs_TriState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace industrial_msgs +{ + + class TriState : public ros::Msg + { + public: + int8_t val; + enum { UNKNOWN = -1 }; + enum { TRUE = 1 }; + enum { ON = 1 }; + enum { ENABLED = 1 }; + enum { HIGH = 1 }; + enum { CLOSED = 1 }; + enum { FALSE = 0 }; + enum { OFF = 0 }; + enum { DISABLED = 0 }; + enum { LOW = 0 }; + enum { OPEN = 0 }; + + TriState(): + val(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.real = this->val; + *(outbuffer + offset + 0) = (u_val.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->val); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_val; + u_val.base = 0; + u_val.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->val = u_val.real; + offset += sizeof(this->val); + return offset; + } + + const char * getType(){ return "industrial_msgs/TriState"; }; + const char * getMD5(){ return "deb03829f3c2d0f1b647fa38d7087952"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/laser_assembler/AssembleScans.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,121 @@ +#ifndef _ROS_SERVICE_AssembleScans_h +#define _ROS_SERVICE_AssembleScans_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "sensor_msgs/PointCloud.h" + +namespace laser_assembler +{ + +static const char ASSEMBLESCANS[] = "laser_assembler/AssembleScans"; + + class AssembleScansRequest : public ros::Msg + { + public: + ros::Time begin; + ros::Time end; + + AssembleScansRequest(): + begin(), + end() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->begin.sec); + *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->begin.nsec); + *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->end.sec); + *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->end.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->begin.sec = ((uint32_t) (*(inbuffer + offset))); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->begin.sec); + this->begin.nsec = ((uint32_t) (*(inbuffer + offset))); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->begin.nsec); + this->end.sec = ((uint32_t) (*(inbuffer + offset))); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->end.sec); + this->end.nsec = ((uint32_t) (*(inbuffer + offset))); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->end.nsec); + return offset; + } + + const char * getType(){ return ASSEMBLESCANS; }; + const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; }; + + }; + + class AssembleScansResponse : public ros::Msg + { + public: + sensor_msgs::PointCloud cloud; + + AssembleScansResponse(): + cloud() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->cloud.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->cloud.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return ASSEMBLESCANS; }; + const char * getMD5(){ return "4217b28a903e4ad7869a83b3653110ff"; }; + + }; + + class AssembleScans { + public: + typedef AssembleScansRequest Request; + typedef AssembleScansResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/laser_assembler/AssembleScans2.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,121 @@ +#ifndef _ROS_SERVICE_AssembleScans2_h +#define _ROS_SERVICE_AssembleScans2_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/PointCloud2.h" +#include "ros/time.h" + +namespace laser_assembler +{ + +static const char ASSEMBLESCANS2[] = "laser_assembler/AssembleScans2"; + + class AssembleScans2Request : public ros::Msg + { + public: + ros::Time begin; + ros::Time end; + + AssembleScans2Request(): + begin(), + end() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->begin.sec); + *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->begin.nsec); + *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->end.sec); + *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->end.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->begin.sec = ((uint32_t) (*(inbuffer + offset))); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->begin.sec); + this->begin.nsec = ((uint32_t) (*(inbuffer + offset))); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->begin.nsec); + this->end.sec = ((uint32_t) (*(inbuffer + offset))); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->end.sec); + this->end.nsec = ((uint32_t) (*(inbuffer + offset))); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->end.nsec); + return offset; + } + + const char * getType(){ return ASSEMBLESCANS2; }; + const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; }; + + }; + + class AssembleScans2Response : public ros::Msg + { + public: + sensor_msgs::PointCloud2 cloud; + + AssembleScans2Response(): + cloud() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->cloud.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->cloud.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return ASSEMBLESCANS2; }; + const char * getMD5(){ return "96cec5374164b3b3d1d7ef5d7628a7ed"; }; + + }; + + class AssembleScans2 { + public: + typedef AssembleScans2Request Request; + typedef AssembleScans2Response Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/CartesianGains.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,83 @@ +#ifndef _ROS_manipulation_msgs_CartesianGains_h +#define _ROS_manipulation_msgs_CartesianGains_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace manipulation_msgs +{ + + class CartesianGains : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t gains_length; + float st_gains; + float * gains; + uint8_t fixed_frame_length; + float st_fixed_frame; + float * fixed_frame; + + CartesianGains(): + header(), + gains_length(0), gains(NULL), + fixed_frame_length(0), fixed_frame(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = gains_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < gains_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->gains[i]); + } + *(outbuffer + offset++) = fixed_frame_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fixed_frame_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->fixed_frame[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t gains_lengthT = *(inbuffer + offset++); + if(gains_lengthT > gains_length) + this->gains = (float*)realloc(this->gains, gains_lengthT * sizeof(float)); + offset += 3; + gains_length = gains_lengthT; + for( uint8_t i = 0; i < gains_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_gains)); + memcpy( &(this->gains[i]), &(this->st_gains), sizeof(float)); + } + uint8_t fixed_frame_lengthT = *(inbuffer + offset++); + if(fixed_frame_lengthT > fixed_frame_length) + this->fixed_frame = (float*)realloc(this->fixed_frame, fixed_frame_lengthT * sizeof(float)); + offset += 3; + fixed_frame_length = fixed_frame_lengthT; + for( uint8_t i = 0; i < fixed_frame_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_fixed_frame)); + memcpy( &(this->fixed_frame[i]), &(this->st_fixed_frame), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "manipulation_msgs/CartesianGains"; }; + const char * getMD5(){ return "ab347f046ca5736a156ec424cbb63635"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/ClusterBoundingBox.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_manipulation_msgs_ClusterBoundingBox_h +#define _ROS_manipulation_msgs_ClusterBoundingBox_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" +#include "geometry_msgs/Vector3.h" + +namespace manipulation_msgs +{ + + class ClusterBoundingBox : public ros::Msg + { + public: + geometry_msgs::PoseStamped pose_stamped; + geometry_msgs::Vector3 dimensions; + + ClusterBoundingBox(): + pose_stamped(), + dimensions() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->pose_stamped.serialize(outbuffer + offset); + offset += this->dimensions.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->pose_stamped.deserialize(inbuffer + offset); + offset += this->dimensions.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "manipulation_msgs/ClusterBoundingBox"; }; + const char * getMD5(){ return "9bf2b7a44ad666dc3a6a2bbc21782dad"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/Grasp.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,136 @@ +#ifndef _ROS_manipulation_msgs_Grasp_h +#define _ROS_manipulation_msgs_Grasp_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/JointState.h" +#include "geometry_msgs/PoseStamped.h" +#include "manipulation_msgs/GripperTranslation.h" + +namespace manipulation_msgs +{ + + class Grasp : public ros::Msg + { + public: + const char* id; + sensor_msgs::JointState pre_grasp_posture; + sensor_msgs::JointState grasp_posture; + geometry_msgs::PoseStamped grasp_pose; + float grasp_quality; + manipulation_msgs::GripperTranslation approach; + manipulation_msgs::GripperTranslation retreat; + float max_contact_force; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + + Grasp(): + id(""), + pre_grasp_posture(), + grasp_posture(), + grasp_pose(), + grasp_quality(0), + approach(), + retreat(), + max_contact_force(0), + allowed_touch_objects_length(0), allowed_touch_objects(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->pre_grasp_posture.serialize(outbuffer + offset); + offset += this->grasp_posture.serialize(outbuffer + offset); + offset += this->grasp_pose.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->grasp_quality); + offset += this->approach.serialize(outbuffer + offset); + offset += this->retreat.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_max_contact_force; + u_max_contact_force.real = this->max_contact_force; + *(outbuffer + offset + 0) = (u_max_contact_force.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_contact_force.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_contact_force.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_contact_force.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_contact_force); + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->pre_grasp_posture.deserialize(inbuffer + offset); + offset += this->grasp_posture.deserialize(inbuffer + offset); + offset += this->grasp_pose.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->grasp_quality)); + offset += this->approach.deserialize(inbuffer + offset); + offset += this->retreat.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_max_contact_force; + u_max_contact_force.base = 0; + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_contact_force = u_max_contact_force.real; + offset += sizeof(this->max_contact_force); + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "manipulation_msgs/Grasp"; }; + const char * getMD5(){ return "83bd11da422ea1917259ee456c0e315a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanning.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,190 @@ +#ifndef _ROS_SERVICE_GraspPlanning_h +#define _ROS_SERVICE_GraspPlanning_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/GraspPlanningErrorCode.h" +#include "manipulation_msgs/GraspableObject.h" +#include "manipulation_msgs/Grasp.h" + +namespace manipulation_msgs +{ + +static const char GRASPPLANNING[] = "manipulation_msgs/GraspPlanning"; + + class GraspPlanningRequest : public ros::Msg + { + public: + const char* arm_name; + manipulation_msgs::GraspableObject target; + const char* collision_object_name; + const char* collision_support_surface_name; + uint8_t grasps_to_evaluate_length; + manipulation_msgs::Grasp st_grasps_to_evaluate; + manipulation_msgs::Grasp * grasps_to_evaluate; + uint8_t movable_obstacles_length; + manipulation_msgs::GraspableObject st_movable_obstacles; + manipulation_msgs::GraspableObject * movable_obstacles; + + GraspPlanningRequest(): + arm_name(""), + target(), + collision_object_name(""), + collision_support_surface_name(""), + grasps_to_evaluate_length(0), grasps_to_evaluate(NULL), + movable_obstacles_length(0), movable_obstacles(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_arm_name = strlen(this->arm_name); + memcpy(outbuffer + offset, &length_arm_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->arm_name, length_arm_name); + offset += length_arm_name; + offset += this->target.serialize(outbuffer + offset); + uint32_t length_collision_object_name = strlen(this->collision_object_name); + memcpy(outbuffer + offset, &length_collision_object_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision_object_name, length_collision_object_name); + offset += length_collision_object_name; + uint32_t length_collision_support_surface_name = strlen(this->collision_support_surface_name); + memcpy(outbuffer + offset, &length_collision_support_surface_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision_support_surface_name, length_collision_support_surface_name); + offset += length_collision_support_surface_name; + *(outbuffer + offset++) = grasps_to_evaluate_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){ + offset += this->grasps_to_evaluate[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = movable_obstacles_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < movable_obstacles_length; i++){ + offset += this->movable_obstacles[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_arm_name; + memcpy(&length_arm_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_arm_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_arm_name-1]=0; + this->arm_name = (char *)(inbuffer + offset-1); + offset += length_arm_name; + offset += this->target.deserialize(inbuffer + offset); + uint32_t length_collision_object_name; + memcpy(&length_collision_object_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision_object_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision_object_name-1]=0; + this->collision_object_name = (char *)(inbuffer + offset-1); + offset += length_collision_object_name; + uint32_t length_collision_support_surface_name; + memcpy(&length_collision_support_surface_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision_support_surface_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision_support_surface_name-1]=0; + this->collision_support_surface_name = (char *)(inbuffer + offset-1); + offset += length_collision_support_surface_name; + uint8_t grasps_to_evaluate_lengthT = *(inbuffer + offset++); + if(grasps_to_evaluate_lengthT > grasps_to_evaluate_length) + this->grasps_to_evaluate = (manipulation_msgs::Grasp*)realloc(this->grasps_to_evaluate, grasps_to_evaluate_lengthT * sizeof(manipulation_msgs::Grasp)); + offset += 3; + grasps_to_evaluate_length = grasps_to_evaluate_lengthT; + for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){ + offset += this->st_grasps_to_evaluate.deserialize(inbuffer + offset); + memcpy( &(this->grasps_to_evaluate[i]), &(this->st_grasps_to_evaluate), sizeof(manipulation_msgs::Grasp)); + } + uint8_t movable_obstacles_lengthT = *(inbuffer + offset++); + if(movable_obstacles_lengthT > movable_obstacles_length) + this->movable_obstacles = (manipulation_msgs::GraspableObject*)realloc(this->movable_obstacles, movable_obstacles_lengthT * sizeof(manipulation_msgs::GraspableObject)); + offset += 3; + movable_obstacles_length = movable_obstacles_lengthT; + for( uint8_t i = 0; i < movable_obstacles_length; i++){ + offset += this->st_movable_obstacles.deserialize(inbuffer + offset); + memcpy( &(this->movable_obstacles[i]), &(this->st_movable_obstacles), sizeof(manipulation_msgs::GraspableObject)); + } + return offset; + } + + const char * getType(){ return GRASPPLANNING; }; + const char * getMD5(){ return "077dca08a07415d82d6ab047890161f4"; }; + + }; + + class GraspPlanningResponse : public ros::Msg + { + public: + uint8_t grasps_length; + manipulation_msgs::Grasp st_grasps; + manipulation_msgs::Grasp * grasps; + manipulation_msgs::GraspPlanningErrorCode error_code; + + GraspPlanningResponse(): + grasps_length(0), grasps(NULL), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = grasps_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->grasps[i].serialize(outbuffer + offset); + } + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t grasps_lengthT = *(inbuffer + offset++); + if(grasps_lengthT > grasps_length) + this->grasps = (manipulation_msgs::Grasp*)realloc(this->grasps, grasps_lengthT * sizeof(manipulation_msgs::Grasp)); + offset += 3; + grasps_length = grasps_lengthT; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->st_grasps.deserialize(inbuffer + offset); + memcpy( &(this->grasps[i]), &(this->st_grasps), sizeof(manipulation_msgs::Grasp)); + } + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GRASPPLANNING; }; + const char * getMD5(){ return "ff7a88c4aec40207164535a24dc9c440"; }; + + }; + + class GraspPlanning { + public: + typedef GraspPlanningRequest Request; + typedef GraspPlanningResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningAction_h +#define _ROS_manipulation_msgs_GraspPlanningAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/GraspPlanningActionGoal.h" +#include "manipulation_msgs/GraspPlanningActionResult.h" +#include "manipulation_msgs/GraspPlanningActionFeedback.h" + +namespace manipulation_msgs +{ + + class GraspPlanningAction : public ros::Msg + { + public: + manipulation_msgs::GraspPlanningActionGoal action_goal; + manipulation_msgs::GraspPlanningActionResult action_result; + manipulation_msgs::GraspPlanningActionFeedback action_feedback; + + GraspPlanningAction(): + 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 "manipulation_msgs/GraspPlanningAction"; }; + const char * getMD5(){ return "f2d7ee4c83f481d31e151ec1b1f209b4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningActionFeedback_h +#define _ROS_manipulation_msgs_GraspPlanningActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "manipulation_msgs/GraspPlanningFeedback.h" + +namespace manipulation_msgs +{ + + class GraspPlanningActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + manipulation_msgs::GraspPlanningFeedback feedback; + + GraspPlanningActionFeedback(): + 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 "manipulation_msgs/GraspPlanningActionFeedback"; }; + const char * getMD5(){ return "25a75a7c3117e1e7efda49b65ff22a06"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningActionGoal_h +#define _ROS_manipulation_msgs_GraspPlanningActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "manipulation_msgs/GraspPlanningGoal.h" + +namespace manipulation_msgs +{ + + class GraspPlanningActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + manipulation_msgs::GraspPlanningGoal goal; + + GraspPlanningActionGoal(): + 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 "manipulation_msgs/GraspPlanningActionGoal"; }; + const char * getMD5(){ return "51f78205082ab7818f66534367bff5f5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningActionResult_h +#define _ROS_manipulation_msgs_GraspPlanningActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "manipulation_msgs/GraspPlanningResult.h" + +namespace manipulation_msgs +{ + + class GraspPlanningActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + manipulation_msgs::GraspPlanningResult result; + + GraspPlanningActionResult(): + 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 "manipulation_msgs/GraspPlanningActionResult"; }; + const char * getMD5(){ return "3e6fbb82747590d8df5c4c99a3c657e8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningErrorCode.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningErrorCode_h +#define _ROS_manipulation_msgs_GraspPlanningErrorCode_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace manipulation_msgs +{ + + class GraspPlanningErrorCode : public ros::Msg + { + public: + int32_t value; + enum { SUCCESS = 0 }; + enum { TF_ERROR = 1 }; + enum { OTHER_ERROR = 2 }; + + GraspPlanningErrorCode(): + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.real = this->value; + *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.base = 0; + u_value.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->value = u_value.real; + offset += sizeof(this->value); + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspPlanningErrorCode"; }; + const char * getMD5(){ return "d0cbf262cc3d8075a46b994eef1bdb2a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningFeedback_h +#define _ROS_manipulation_msgs_GraspPlanningFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/Grasp.h" + +namespace manipulation_msgs +{ + + class GraspPlanningFeedback : public ros::Msg + { + public: + uint8_t grasps_length; + manipulation_msgs::Grasp st_grasps; + manipulation_msgs::Grasp * grasps; + + GraspPlanningFeedback(): + grasps_length(0), grasps(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = grasps_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->grasps[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t grasps_lengthT = *(inbuffer + offset++); + if(grasps_lengthT > grasps_length) + this->grasps = (manipulation_msgs::Grasp*)realloc(this->grasps, grasps_lengthT * sizeof(manipulation_msgs::Grasp)); + offset += 3; + grasps_length = grasps_lengthT; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->st_grasps.deserialize(inbuffer + offset); + memcpy( &(this->grasps[i]), &(this->st_grasps), sizeof(manipulation_msgs::Grasp)); + } + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspPlanningFeedback"; }; + const char * getMD5(){ return "0b493f83ef98679f05dc681205fbe54c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,132 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningGoal_h +#define _ROS_manipulation_msgs_GraspPlanningGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/GraspableObject.h" +#include "manipulation_msgs/Grasp.h" + +namespace manipulation_msgs +{ + + class GraspPlanningGoal : public ros::Msg + { + public: + const char* arm_name; + manipulation_msgs::GraspableObject target; + const char* collision_object_name; + const char* collision_support_surface_name; + uint8_t grasps_to_evaluate_length; + manipulation_msgs::Grasp st_grasps_to_evaluate; + manipulation_msgs::Grasp * grasps_to_evaluate; + uint8_t movable_obstacles_length; + manipulation_msgs::GraspableObject st_movable_obstacles; + manipulation_msgs::GraspableObject * movable_obstacles; + + GraspPlanningGoal(): + arm_name(""), + target(), + collision_object_name(""), + collision_support_surface_name(""), + grasps_to_evaluate_length(0), grasps_to_evaluate(NULL), + movable_obstacles_length(0), movable_obstacles(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_arm_name = strlen(this->arm_name); + memcpy(outbuffer + offset, &length_arm_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->arm_name, length_arm_name); + offset += length_arm_name; + offset += this->target.serialize(outbuffer + offset); + uint32_t length_collision_object_name = strlen(this->collision_object_name); + memcpy(outbuffer + offset, &length_collision_object_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision_object_name, length_collision_object_name); + offset += length_collision_object_name; + uint32_t length_collision_support_surface_name = strlen(this->collision_support_surface_name); + memcpy(outbuffer + offset, &length_collision_support_surface_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision_support_surface_name, length_collision_support_surface_name); + offset += length_collision_support_surface_name; + *(outbuffer + offset++) = grasps_to_evaluate_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){ + offset += this->grasps_to_evaluate[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = movable_obstacles_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < movable_obstacles_length; i++){ + offset += this->movable_obstacles[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_arm_name; + memcpy(&length_arm_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_arm_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_arm_name-1]=0; + this->arm_name = (char *)(inbuffer + offset-1); + offset += length_arm_name; + offset += this->target.deserialize(inbuffer + offset); + uint32_t length_collision_object_name; + memcpy(&length_collision_object_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision_object_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision_object_name-1]=0; + this->collision_object_name = (char *)(inbuffer + offset-1); + offset += length_collision_object_name; + uint32_t length_collision_support_surface_name; + memcpy(&length_collision_support_surface_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision_support_surface_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision_support_surface_name-1]=0; + this->collision_support_surface_name = (char *)(inbuffer + offset-1); + offset += length_collision_support_surface_name; + uint8_t grasps_to_evaluate_lengthT = *(inbuffer + offset++); + if(grasps_to_evaluate_lengthT > grasps_to_evaluate_length) + this->grasps_to_evaluate = (manipulation_msgs::Grasp*)realloc(this->grasps_to_evaluate, grasps_to_evaluate_lengthT * sizeof(manipulation_msgs::Grasp)); + offset += 3; + grasps_to_evaluate_length = grasps_to_evaluate_lengthT; + for( uint8_t i = 0; i < grasps_to_evaluate_length; i++){ + offset += this->st_grasps_to_evaluate.deserialize(inbuffer + offset); + memcpy( &(this->grasps_to_evaluate[i]), &(this->st_grasps_to_evaluate), sizeof(manipulation_msgs::Grasp)); + } + uint8_t movable_obstacles_lengthT = *(inbuffer + offset++); + if(movable_obstacles_lengthT > movable_obstacles_length) + this->movable_obstacles = (manipulation_msgs::GraspableObject*)realloc(this->movable_obstacles, movable_obstacles_lengthT * sizeof(manipulation_msgs::GraspableObject)); + offset += 3; + movable_obstacles_length = movable_obstacles_lengthT; + for( uint8_t i = 0; i < movable_obstacles_length; i++){ + offset += this->st_movable_obstacles.deserialize(inbuffer + offset); + memcpy( &(this->movable_obstacles[i]), &(this->st_movable_obstacles), sizeof(manipulation_msgs::GraspableObject)); + } + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspPlanningGoal"; }; + const char * getMD5(){ return "077dca08a07415d82d6ab047890161f4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspPlanningResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_manipulation_msgs_GraspPlanningResult_h +#define _ROS_manipulation_msgs_GraspPlanningResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/Grasp.h" +#include "manipulation_msgs/GraspPlanningErrorCode.h" + +namespace manipulation_msgs +{ + + class GraspPlanningResult : public ros::Msg + { + public: + uint8_t grasps_length; + manipulation_msgs::Grasp st_grasps; + manipulation_msgs::Grasp * grasps; + manipulation_msgs::GraspPlanningErrorCode error_code; + + GraspPlanningResult(): + grasps_length(0), grasps(NULL), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = grasps_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->grasps[i].serialize(outbuffer + offset); + } + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t grasps_lengthT = *(inbuffer + offset++); + if(grasps_lengthT > grasps_length) + this->grasps = (manipulation_msgs::Grasp*)realloc(this->grasps, grasps_lengthT * sizeof(manipulation_msgs::Grasp)); + offset += 3; + grasps_length = grasps_lengthT; + for( uint8_t i = 0; i < grasps_length; i++){ + offset += this->st_grasps.deserialize(inbuffer + offset); + memcpy( &(this->grasps[i]), &(this->st_grasps), sizeof(manipulation_msgs::Grasp)); + } + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspPlanningResult"; }; + const char * getMD5(){ return "ff7a88c4aec40207164535a24dc9c440"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_manipulation_msgs_GraspResult_h +#define _ROS_manipulation_msgs_GraspResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace manipulation_msgs +{ + + class GraspResult : public ros::Msg + { + public: + int32_t result_code; + bool continuation_possible; + enum { SUCCESS = 1 }; + enum { GRASP_OUT_OF_REACH = 2 }; + enum { GRASP_IN_COLLISION = 3 }; + enum { GRASP_UNFEASIBLE = 4 }; + enum { PREGRASP_OUT_OF_REACH = 5 }; + enum { PREGRASP_IN_COLLISION = 6 }; + enum { PREGRASP_UNFEASIBLE = 7 }; + enum { LIFT_OUT_OF_REACH = 8 }; + enum { LIFT_IN_COLLISION = 9 }; + enum { LIFT_UNFEASIBLE = 10 }; + enum { MOVE_ARM_FAILED = 11 }; + enum { GRASP_FAILED = 12 }; + enum { LIFT_FAILED = 13 }; + enum { RETREAT_FAILED = 14 }; + + GraspResult(): + result_code(0), + continuation_possible(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result_code; + u_result_code.real = this->result_code; + *(outbuffer + offset + 0) = (u_result_code.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_result_code.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_result_code.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_result_code.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->result_code); + union { + bool real; + uint8_t base; + } u_continuation_possible; + u_continuation_possible.real = this->continuation_possible; + *(outbuffer + offset + 0) = (u_continuation_possible.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->continuation_possible); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result_code; + u_result_code.base = 0; + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->result_code = u_result_code.real; + offset += sizeof(this->result_code); + union { + bool real; + uint8_t base; + } u_continuation_possible; + u_continuation_possible.base = 0; + u_continuation_possible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->continuation_possible = u_continuation_possible.real; + offset += sizeof(this->continuation_possible); + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspResult"; }; + const char * getMD5(){ return "c8a909da895cdddc0630aafd59848191"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspableObject.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,101 @@ +#ifndef _ROS_manipulation_msgs_GraspableObject_h +#define _ROS_manipulation_msgs_GraspableObject_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "household_objects_database_msgs/DatabaseModelPose.h" +#include "sensor_msgs/PointCloud.h" +#include "manipulation_msgs/SceneRegion.h" + +namespace manipulation_msgs +{ + + class GraspableObject : public ros::Msg + { + public: + const char* reference_frame_id; + uint8_t potential_models_length; + household_objects_database_msgs::DatabaseModelPose st_potential_models; + household_objects_database_msgs::DatabaseModelPose * potential_models; + sensor_msgs::PointCloud cluster; + manipulation_msgs::SceneRegion region; + const char* collision_name; + + GraspableObject(): + reference_frame_id(""), + potential_models_length(0), potential_models(NULL), + cluster(), + region(), + collision_name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_reference_frame_id = strlen(this->reference_frame_id); + memcpy(outbuffer + offset, &length_reference_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->reference_frame_id, length_reference_frame_id); + offset += length_reference_frame_id; + *(outbuffer + offset++) = potential_models_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < potential_models_length; i++){ + offset += this->potential_models[i].serialize(outbuffer + offset); + } + offset += this->cluster.serialize(outbuffer + offset); + offset += this->region.serialize(outbuffer + offset); + uint32_t length_collision_name = strlen(this->collision_name); + memcpy(outbuffer + offset, &length_collision_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->collision_name, length_collision_name); + offset += length_collision_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_reference_frame_id; + memcpy(&length_reference_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_reference_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_reference_frame_id-1]=0; + this->reference_frame_id = (char *)(inbuffer + offset-1); + offset += length_reference_frame_id; + uint8_t potential_models_lengthT = *(inbuffer + offset++); + if(potential_models_lengthT > potential_models_length) + this->potential_models = (household_objects_database_msgs::DatabaseModelPose*)realloc(this->potential_models, potential_models_lengthT * sizeof(household_objects_database_msgs::DatabaseModelPose)); + offset += 3; + potential_models_length = potential_models_lengthT; + for( uint8_t i = 0; i < potential_models_length; i++){ + offset += this->st_potential_models.deserialize(inbuffer + offset); + memcpy( &(this->potential_models[i]), &(this->st_potential_models), sizeof(household_objects_database_msgs::DatabaseModelPose)); + } + offset += this->cluster.deserialize(inbuffer + offset); + offset += this->region.deserialize(inbuffer + offset); + uint32_t length_collision_name; + memcpy(&length_collision_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_collision_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_collision_name-1]=0; + this->collision_name = (char *)(inbuffer + offset-1); + offset += length_collision_name; + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspableObject"; }; + const char * getMD5(){ return "e2efd13d8e2bbb4697a5d71f167bceaa"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GraspableObjectList.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,95 @@ +#ifndef _ROS_manipulation_msgs_GraspableObjectList_h +#define _ROS_manipulation_msgs_GraspableObjectList_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "manipulation_msgs/GraspableObject.h" +#include "sensor_msgs/Image.h" +#include "sensor_msgs/CameraInfo.h" +#include "shape_msgs/Mesh.h" +#include "geometry_msgs/Pose.h" + +namespace manipulation_msgs +{ + + class GraspableObjectList : public ros::Msg + { + public: + uint8_t graspable_objects_length; + manipulation_msgs::GraspableObject st_graspable_objects; + manipulation_msgs::GraspableObject * graspable_objects; + sensor_msgs::Image image; + sensor_msgs::CameraInfo camera_info; + uint8_t meshes_length; + shape_msgs::Mesh st_meshes; + shape_msgs::Mesh * meshes; + geometry_msgs::Pose reference_to_camera; + + GraspableObjectList(): + graspable_objects_length(0), graspable_objects(NULL), + image(), + camera_info(), + meshes_length(0), meshes(NULL), + reference_to_camera() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = graspable_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < graspable_objects_length; i++){ + offset += this->graspable_objects[i].serialize(outbuffer + offset); + } + offset += this->image.serialize(outbuffer + offset); + offset += this->camera_info.serialize(outbuffer + offset); + *(outbuffer + offset++) = meshes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->meshes[i].serialize(outbuffer + offset); + } + offset += this->reference_to_camera.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t graspable_objects_lengthT = *(inbuffer + offset++); + if(graspable_objects_lengthT > graspable_objects_length) + this->graspable_objects = (manipulation_msgs::GraspableObject*)realloc(this->graspable_objects, graspable_objects_lengthT * sizeof(manipulation_msgs::GraspableObject)); + offset += 3; + graspable_objects_length = graspable_objects_lengthT; + for( uint8_t i = 0; i < graspable_objects_length; i++){ + offset += this->st_graspable_objects.deserialize(inbuffer + offset); + memcpy( &(this->graspable_objects[i]), &(this->st_graspable_objects), sizeof(manipulation_msgs::GraspableObject)); + } + offset += this->image.deserialize(inbuffer + offset); + offset += this->camera_info.deserialize(inbuffer + offset); + uint8_t meshes_lengthT = *(inbuffer + offset++); + if(meshes_lengthT > meshes_length) + this->meshes = (shape_msgs::Mesh*)realloc(this->meshes, meshes_lengthT * sizeof(shape_msgs::Mesh)); + offset += 3; + meshes_length = meshes_lengthT; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->st_meshes.deserialize(inbuffer + offset); + memcpy( &(this->meshes[i]), &(this->st_meshes), sizeof(shape_msgs::Mesh)); + } + offset += this->reference_to_camera.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "manipulation_msgs/GraspableObjectList"; }; + const char * getMD5(){ return "d67571f2982f1b7115de1e0027319109"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/GripperTranslation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,89 @@ +#ifndef _ROS_manipulation_msgs_GripperTranslation_h +#define _ROS_manipulation_msgs_GripperTranslation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3Stamped.h" + +namespace manipulation_msgs +{ + + class GripperTranslation : public ros::Msg + { + public: + geometry_msgs::Vector3Stamped direction; + float desired_distance; + float min_distance; + + GripperTranslation(): + direction(), + desired_distance(0), + min_distance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->direction.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_desired_distance; + u_desired_distance.real = this->desired_distance; + *(outbuffer + offset + 0) = (u_desired_distance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_desired_distance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_desired_distance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_desired_distance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->desired_distance); + union { + float real; + uint32_t base; + } u_min_distance; + u_min_distance.real = this->min_distance; + *(outbuffer + offset + 0) = (u_min_distance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_distance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_distance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_distance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_distance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->direction.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_desired_distance; + u_desired_distance.base = 0; + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->desired_distance = u_desired_distance.real; + offset += sizeof(this->desired_distance); + union { + float real; + uint32_t base; + } u_min_distance; + u_min_distance.base = 0; + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_distance = u_min_distance.real; + offset += sizeof(this->min_distance); + return offset; + } + + const char * getType(){ return "manipulation_msgs/GripperTranslation"; }; + const char * getMD5(){ return "b53bc0ad0f717cdec3b0e42dec300121"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/ManipulationPhase.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_manipulation_msgs_ManipulationPhase_h +#define _ROS_manipulation_msgs_ManipulationPhase_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace manipulation_msgs +{ + + class ManipulationPhase : public ros::Msg + { + public: + int32_t phase; + enum { CHECKING_FEASIBILITY = 0 }; + enum { MOVING_TO_PREGRASP = 1 }; + enum { MOVING_TO_GRASP = 2 }; + enum { CLOSING = 3 }; + enum { ADJUSTING_GRASP = 4 }; + enum { LIFTING = 5 }; + enum { MOVING_WITH_OBJECT = 6 }; + enum { MOVING_TO_PLACE = 7 }; + enum { PLACING = 8 }; + enum { OPENING = 9 }; + enum { RETREATING = 10 }; + enum { MOVING_WITHOUT_OBJECT = 11 }; + enum { SHAKING = 12 }; + enum { SUCCEEDED = 13 }; + enum { FAILED = 14 }; + enum { ABORTED = 15 }; + enum { HOLDING_OBJECT = 16 }; + + ManipulationPhase(): + phase(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_phase; + u_phase.real = this->phase; + *(outbuffer + offset + 0) = (u_phase.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_phase.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_phase.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_phase.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->phase); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_phase; + u_phase.base = 0; + u_phase.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_phase.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_phase.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_phase.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->phase = u_phase.real; + offset += sizeof(this->phase); + return offset; + } + + const char * getType(){ return "manipulation_msgs/ManipulationPhase"; }; + const char * getMD5(){ return "2c824c847a35d8fd9277d324a3723378"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/ManipulationResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_manipulation_msgs_ManipulationResult_h +#define _ROS_manipulation_msgs_ManipulationResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace manipulation_msgs +{ + + class ManipulationResult : public ros::Msg + { + public: + int32_t value; + enum { SUCCESS = 1 }; + enum { UNFEASIBLE = -1 }; + enum { FAILED = -2 }; + enum { ERROR = -3 }; + enum { ARM_MOVEMENT_PREVENTED = -4 }; + enum { LIFT_FAILED = -5 }; + enum { RETREAT_FAILED = -6 }; + enum { CANCELLED = -7 }; + + ManipulationResult(): + value(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.real = this->value; + *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_value.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_value.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_value.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->value); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_value; + u_value.base = 0; + u_value.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_value.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->value = u_value.real; + offset += sizeof(this->value); + return offset; + } + + const char * getType(){ return "manipulation_msgs/ManipulationResult"; }; + const char * getMD5(){ return "85f8d010e045fcb335637fc8fc59184b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/PlaceLocation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,105 @@ +#ifndef _ROS_manipulation_msgs_PlaceLocation_h +#define _ROS_manipulation_msgs_PlaceLocation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/JointState.h" +#include "geometry_msgs/PoseStamped.h" +#include "manipulation_msgs/GripperTranslation.h" + +namespace manipulation_msgs +{ + + class PlaceLocation : public ros::Msg + { + public: + const char* id; + sensor_msgs::JointState post_place_posture; + geometry_msgs::PoseStamped place_pose; + manipulation_msgs::GripperTranslation approach; + manipulation_msgs::GripperTranslation retreat; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + + PlaceLocation(): + id(""), + post_place_posture(), + place_pose(), + approach(), + retreat(), + allowed_touch_objects_length(0), allowed_touch_objects(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->post_place_posture.serialize(outbuffer + offset); + offset += this->place_pose.serialize(outbuffer + offset); + offset += this->approach.serialize(outbuffer + offset); + offset += this->retreat.serialize(outbuffer + offset); + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->post_place_posture.deserialize(inbuffer + offset); + offset += this->place_pose.deserialize(inbuffer + offset); + offset += this->approach.deserialize(inbuffer + offset); + offset += this->retreat.deserialize(inbuffer + offset); + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "manipulation_msgs/PlaceLocation"; }; + const char * getMD5(){ return "0139dab9852add0e64233c5fb3b8a25a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/PlaceLocationResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,91 @@ +#ifndef _ROS_manipulation_msgs_PlaceLocationResult_h +#define _ROS_manipulation_msgs_PlaceLocationResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace manipulation_msgs +{ + + class PlaceLocationResult : public ros::Msg + { + public: + int32_t result_code; + bool continuation_possible; + enum { SUCCESS = 1 }; + enum { PLACE_OUT_OF_REACH = 2 }; + enum { PLACE_IN_COLLISION = 3 }; + enum { PLACE_UNFEASIBLE = 4 }; + enum { PREPLACE_OUT_OF_REACH = 5 }; + enum { PREPLACE_IN_COLLISION = 6 }; + enum { PREPLACE_UNFEASIBLE = 7 }; + enum { RETREAT_OUT_OF_REACH = 8 }; + enum { RETREAT_IN_COLLISION = 9 }; + enum { RETREAT_UNFEASIBLE = 10 }; + enum { MOVE_ARM_FAILED = 11 }; + enum { PLACE_FAILED = 12 }; + enum { RETREAT_FAILED = 13 }; + + PlaceLocationResult(): + result_code(0), + continuation_possible(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result_code; + u_result_code.real = this->result_code; + *(outbuffer + offset + 0) = (u_result_code.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_result_code.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_result_code.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_result_code.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->result_code); + union { + bool real; + uint8_t base; + } u_continuation_possible; + u_continuation_possible.real = this->continuation_possible; + *(outbuffer + offset + 0) = (u_continuation_possible.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->continuation_possible); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_result_code; + u_result_code.base = 0; + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_result_code.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->result_code = u_result_code.real; + offset += sizeof(this->result_code); + union { + bool real; + uint8_t base; + } u_continuation_possible; + u_continuation_possible.base = 0; + u_continuation_possible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->continuation_possible = u_continuation_possible.real; + offset += sizeof(this->continuation_possible); + return offset; + } + + const char * getType(){ return "manipulation_msgs/PlaceLocationResult"; }; + const char * getMD5(){ return "8dd9edc3a2a98cab298ca81031224cda"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/manipulation_msgs/SceneRegion.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,106 @@ +#ifndef _ROS_manipulation_msgs_SceneRegion_h +#define _ROS_manipulation_msgs_SceneRegion_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/PointCloud2.h" +#include "sensor_msgs/Image.h" +#include "sensor_msgs/CameraInfo.h" +#include "geometry_msgs/PoseStamped.h" +#include "geometry_msgs/Vector3.h" + +namespace manipulation_msgs +{ + + class SceneRegion : public ros::Msg + { + public: + sensor_msgs::PointCloud2 cloud; + uint8_t mask_length; + int32_t st_mask; + int32_t * mask; + sensor_msgs::Image image; + sensor_msgs::Image disparity_image; + sensor_msgs::CameraInfo cam_info; + geometry_msgs::PoseStamped roi_box_pose; + geometry_msgs::Vector3 roi_box_dims; + + SceneRegion(): + cloud(), + mask_length(0), mask(NULL), + image(), + disparity_image(), + cam_info(), + roi_box_pose(), + roi_box_dims() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->cloud.serialize(outbuffer + offset); + *(outbuffer + offset++) = mask_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < mask_length; i++){ + union { + int32_t real; + uint32_t base; + } u_maski; + u_maski.real = this->mask[i]; + *(outbuffer + offset + 0) = (u_maski.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_maski.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_maski.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_maski.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->mask[i]); + } + offset += this->image.serialize(outbuffer + offset); + offset += this->disparity_image.serialize(outbuffer + offset); + offset += this->cam_info.serialize(outbuffer + offset); + offset += this->roi_box_pose.serialize(outbuffer + offset); + offset += this->roi_box_dims.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->cloud.deserialize(inbuffer + offset); + uint8_t mask_lengthT = *(inbuffer + offset++); + if(mask_lengthT > mask_length) + this->mask = (int32_t*)realloc(this->mask, mask_lengthT * sizeof(int32_t)); + offset += 3; + mask_length = mask_lengthT; + for( uint8_t i = 0; i < mask_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_mask; + u_st_mask.base = 0; + u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_mask = u_st_mask.real; + offset += sizeof(this->st_mask); + memcpy( &(this->mask[i]), &(this->st_mask), sizeof(int32_t)); + } + offset += this->image.deserialize(inbuffer + offset); + offset += this->disparity_image.deserialize(inbuffer + offset); + offset += this->cam_info.deserialize(inbuffer + offset); + offset += this->roi_box_pose.deserialize(inbuffer + offset); + offset += this->roi_box_dims.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "manipulation_msgs/SceneRegion"; }; + const char * getMD5(){ return "0a9ab02b19292633619876c9d247690c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/GetMapROI.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_GetMapROI_h +#define _ROS_SERVICE_GetMapROI_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace map_msgs +{ + +static const char GETMAPROI[] = "map_msgs/GetMapROI"; + + class GetMapROIRequest : public ros::Msg + { + public: + float x; + float y; + float l_x; + float l_y; + + GetMapROIRequest(): + x(0), + y(0), + l_x(0), + l_y(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->x); + offset += serializeAvrFloat64(outbuffer + offset, this->y); + offset += serializeAvrFloat64(outbuffer + offset, this->l_x); + offset += serializeAvrFloat64(outbuffer + offset, this->l_y); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->l_x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->l_y)); + return offset; + } + + const char * getType(){ return GETMAPROI; }; + const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; }; + + }; + + class GetMapROIResponse : public ros::Msg + { + public: + nav_msgs::OccupancyGrid sub_map; + + GetMapROIResponse(): + sub_map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->sub_map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->sub_map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMAPROI; }; + const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; }; + + }; + + class GetMapROI { + public: + typedef GetMapROIRequest Request; + typedef GetMapROIResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/GetPointMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_GetPointMap_h +#define _ROS_SERVICE_GetPointMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/PointCloud2.h" + +namespace map_msgs +{ + +static const char GETPOINTMAP[] = "map_msgs/GetPointMap"; + + class GetPointMapRequest : public ros::Msg + { + public: + + GetPointMapRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETPOINTMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetPointMapResponse : public ros::Msg + { + public: + sensor_msgs::PointCloud2 map; + + GetPointMapResponse(): + map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOINTMAP; }; + const char * getMD5(){ return "b84fbb39505086eb6a62d933c75cb7b4"; }; + + }; + + class GetPointMap { + public: + typedef GetPointMapRequest Request; + typedef GetPointMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/GetPointMapROI.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_GetPointMapROI_h +#define _ROS_SERVICE_GetPointMapROI_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/PointCloud2.h" + +namespace map_msgs +{ + +static const char GETPOINTMAPROI[] = "map_msgs/GetPointMapROI"; + + class GetPointMapROIRequest : public ros::Msg + { + public: + float x; + float y; + float z; + float r; + float l_x; + float l_y; + float l_z; + + GetPointMapROIRequest(): + x(0), + y(0), + z(0), + r(0), + l_x(0), + l_y(0), + l_z(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->x); + offset += serializeAvrFloat64(outbuffer + offset, this->y); + offset += serializeAvrFloat64(outbuffer + offset, this->z); + offset += serializeAvrFloat64(outbuffer + offset, this->r); + offset += serializeAvrFloat64(outbuffer + offset, this->l_x); + offset += serializeAvrFloat64(outbuffer + offset, this->l_y); + offset += serializeAvrFloat64(outbuffer + offset, this->l_z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->r)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->l_x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->l_y)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->l_z)); + return offset; + } + + const char * getType(){ return GETPOINTMAPROI; }; + const char * getMD5(){ return "895f7e437a9a6dd225316872b187a303"; }; + + }; + + class GetPointMapROIResponse : public ros::Msg + { + public: + sensor_msgs::PointCloud2 sub_map; + + GetPointMapROIResponse(): + sub_map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->sub_map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->sub_map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOINTMAPROI; }; + const char * getMD5(){ return "313769f8b0e724525c6463336cbccd63"; }; + + }; + + class GetPointMapROI { + public: + typedef GetPointMapROIRequest Request; + typedef GetPointMapROIResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/OccupancyGridUpdate.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,146 @@ +#ifndef _ROS_map_msgs_OccupancyGridUpdate_h +#define _ROS_map_msgs_OccupancyGridUpdate_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace map_msgs +{ + + class OccupancyGridUpdate : public ros::Msg + { + public: + std_msgs::Header header; + int32_t x; + int32_t y; + uint32_t width; + uint32_t height; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + OccupancyGridUpdate(): + header(), + x(0), + y(0), + width(0), + height(0), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + int32_t real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + int32_t real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + int32_t real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + int32_t real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "map_msgs/OccupancyGridUpdate"; }; + const char * getMD5(){ return "b295be292b335c34718bd939deebe1c9"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/PointCloud2Update.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_map_msgs_PointCloud2Update_h +#define _ROS_map_msgs_PointCloud2Update_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/PointCloud2.h" + +namespace map_msgs +{ + + class PointCloud2Update : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t type; + sensor_msgs::PointCloud2 points; + enum { ADD = 0 }; + enum { DELETE = 1 }; + + PointCloud2Update(): + header(), + type(0), + points() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->type >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->type >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->type >> (8 * 3)) & 0xFF; + offset += sizeof(this->type); + offset += this->points.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->type = ((uint32_t) (*(inbuffer + offset))); + this->type |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->type |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->type |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->type); + offset += this->points.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "map_msgs/PointCloud2Update"; }; + const char * getMD5(){ return "6c58e4f249ae9cd2b24fb1ee0f99195e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/ProjectedMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,51 @@ +#ifndef _ROS_map_msgs_ProjectedMap_h +#define _ROS_map_msgs_ProjectedMap_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace map_msgs +{ + + class ProjectedMap : public ros::Msg + { + public: + nav_msgs::OccupancyGrid map; + float min_z; + float max_z; + + ProjectedMap(): + map(), + min_z(0), + max_z(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->min_z); + offset += serializeAvrFloat64(outbuffer + offset, this->max_z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_z)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_z)); + return offset; + } + + const char * getType(){ return "map_msgs/ProjectedMap"; }; + const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/ProjectedMapInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_map_msgs_ProjectedMapInfo_h +#define _ROS_map_msgs_ProjectedMapInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace map_msgs +{ + + class ProjectedMapInfo : public ros::Msg + { + public: + const char* frame_id; + float x; + float y; + float width; + float height; + float min_z; + float max_z; + + ProjectedMapInfo(): + frame_id(""), + x(0), + y(0), + width(0), + height(0), + min_z(0), + max_z(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_frame_id = strlen(this->frame_id); + memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->frame_id, length_frame_id); + offset += length_frame_id; + offset += serializeAvrFloat64(outbuffer + offset, this->x); + offset += serializeAvrFloat64(outbuffer + offset, this->y); + offset += serializeAvrFloat64(outbuffer + offset, this->width); + offset += serializeAvrFloat64(outbuffer + offset, this->height); + offset += serializeAvrFloat64(outbuffer + offset, this->min_z); + offset += serializeAvrFloat64(outbuffer + offset, this->max_z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_frame_id; + memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_id-1]=0; + this->frame_id = (char *)(inbuffer + offset-1); + offset += length_frame_id; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->width)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->height)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_z)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_z)); + return offset; + } + + const char * getType(){ return "map_msgs/ProjectedMapInfo"; }; + const char * getMD5(){ return "2dc10595ae94de23f22f8a6d2a0eef7a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/ProjectedMapsInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_ProjectedMapsInfo_h +#define _ROS_SERVICE_ProjectedMapsInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "map_msgs/ProjectedMapInfo.h" + +namespace map_msgs +{ + +static const char PROJECTEDMAPSINFO[] = "map_msgs/ProjectedMapsInfo"; + + class ProjectedMapsInfoRequest : public ros::Msg + { + public: + uint8_t projected_maps_info_length; + map_msgs::ProjectedMapInfo st_projected_maps_info; + map_msgs::ProjectedMapInfo * projected_maps_info; + + ProjectedMapsInfoRequest(): + projected_maps_info_length(0), projected_maps_info(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = projected_maps_info_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < projected_maps_info_length; i++){ + offset += this->projected_maps_info[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t projected_maps_info_lengthT = *(inbuffer + offset++); + if(projected_maps_info_lengthT > projected_maps_info_length) + this->projected_maps_info = (map_msgs::ProjectedMapInfo*)realloc(this->projected_maps_info, projected_maps_info_lengthT * sizeof(map_msgs::ProjectedMapInfo)); + offset += 3; + projected_maps_info_length = projected_maps_info_lengthT; + for( uint8_t i = 0; i < projected_maps_info_length; i++){ + offset += this->st_projected_maps_info.deserialize(inbuffer + offset); + memcpy( &(this->projected_maps_info[i]), &(this->st_projected_maps_info), sizeof(map_msgs::ProjectedMapInfo)); + } + return offset; + } + + const char * getType(){ return PROJECTEDMAPSINFO; }; + const char * getMD5(){ return "d7980a33202421c8cd74565e57a4d229"; }; + + }; + + class ProjectedMapsInfoResponse : public ros::Msg + { + public: + + ProjectedMapsInfoResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return PROJECTEDMAPSINFO; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class ProjectedMapsInfo { + public: + typedef ProjectedMapsInfoRequest Request; + typedef ProjectedMapsInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/SaveMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_SaveMap_h +#define _ROS_SERVICE_SaveMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/String.h" + +namespace map_msgs +{ + +static const char SAVEMAP[] = "map_msgs/SaveMap"; + + class SaveMapRequest : public ros::Msg + { + public: + std_msgs::String filename; + + SaveMapRequest(): + filename() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->filename.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->filename.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SAVEMAP; }; + const char * getMD5(){ return "716e25f9d9dc76ceba197f93cbf05dc7"; }; + + }; + + class SaveMapResponse : public ros::Msg + { + public: + + SaveMapResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SAVEMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SaveMap { + public: + typedef SaveMapRequest Request; + typedef SaveMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/map_msgs/SetMapProjections.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_SetMapProjections_h +#define _ROS_SERVICE_SetMapProjections_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "map_msgs/ProjectedMapInfo.h" + +namespace map_msgs +{ + +static const char SETMAPPROJECTIONS[] = "map_msgs/SetMapProjections"; + + class SetMapProjectionsRequest : public ros::Msg + { + public: + + SetMapProjectionsRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SETMAPPROJECTIONS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetMapProjectionsResponse : public ros::Msg + { + public: + uint8_t projected_maps_info_length; + map_msgs::ProjectedMapInfo st_projected_maps_info; + map_msgs::ProjectedMapInfo * projected_maps_info; + + SetMapProjectionsResponse(): + projected_maps_info_length(0), projected_maps_info(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = projected_maps_info_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < projected_maps_info_length; i++){ + offset += this->projected_maps_info[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t projected_maps_info_lengthT = *(inbuffer + offset++); + if(projected_maps_info_lengthT > projected_maps_info_length) + this->projected_maps_info = (map_msgs::ProjectedMapInfo*)realloc(this->projected_maps_info, projected_maps_info_lengthT * sizeof(map_msgs::ProjectedMapInfo)); + offset += 3; + projected_maps_info_length = projected_maps_info_lengthT; + for( uint8_t i = 0; i < projected_maps_info_length; i++){ + offset += this->st_projected_maps_info.deserialize(inbuffer + offset); + memcpy( &(this->projected_maps_info[i]), &(this->st_projected_maps_info), sizeof(map_msgs::ProjectedMapInfo)); + } + return offset; + } + + const char * getType(){ return SETMAPPROJECTIONS; }; + const char * getMD5(){ return "d7980a33202421c8cd74565e57a4d229"; }; + + }; + + class SetMapProjections { + public: + typedef SetMapProjectionsRequest Request; + typedef SetMapProjectionsResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/e188a91d3eaa \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_move_base_msgs_MoveBaseAction_h +#define _ROS_move_base_msgs_MoveBaseAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "move_base_msgs/MoveBaseActionGoal.h" +#include "move_base_msgs/MoveBaseActionResult.h" +#include "move_base_msgs/MoveBaseActionFeedback.h" + +namespace move_base_msgs +{ + + class MoveBaseAction : public ros::Msg + { + public: + move_base_msgs::MoveBaseActionGoal action_goal; + move_base_msgs::MoveBaseActionResult action_result; + move_base_msgs::MoveBaseActionFeedback action_feedback; + + MoveBaseAction(): + 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 "move_base_msgs/MoveBaseAction"; }; + const char * getMD5(){ return "70b6aca7c7f7746d8d1609ad94c80bb8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_move_base_msgs_MoveBaseActionFeedback_h +#define _ROS_move_base_msgs_MoveBaseActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "move_base_msgs/MoveBaseFeedback.h" + +namespace move_base_msgs +{ + + class MoveBaseActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + move_base_msgs::MoveBaseFeedback feedback; + + MoveBaseActionFeedback(): + 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 "move_base_msgs/MoveBaseActionFeedback"; }; + const char * getMD5(){ return "7d1870ff6e0decea702b943b5af0b42e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_move_base_msgs_MoveBaseActionGoal_h +#define _ROS_move_base_msgs_MoveBaseActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "move_base_msgs/MoveBaseGoal.h" + +namespace move_base_msgs +{ + + class MoveBaseActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + move_base_msgs::MoveBaseGoal goal; + + MoveBaseActionGoal(): + 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 "move_base_msgs/MoveBaseActionGoal"; }; + const char * getMD5(){ return "660d6895a1b9a16dce51fbdd9a64a56b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_move_base_msgs_MoveBaseActionResult_h +#define _ROS_move_base_msgs_MoveBaseActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "move_base_msgs/MoveBaseResult.h" + +namespace move_base_msgs +{ + + class MoveBaseActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + move_base_msgs::MoveBaseResult result; + + MoveBaseActionResult(): + 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 "move_base_msgs/MoveBaseActionResult"; }; + const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_move_base_msgs_MoveBaseFeedback_h +#define _ROS_move_base_msgs_MoveBaseFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" + +namespace move_base_msgs +{ + + class MoveBaseFeedback : public ros::Msg + { + public: + geometry_msgs::PoseStamped base_position; + + MoveBaseFeedback(): + base_position() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->base_position.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->base_position.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "move_base_msgs/MoveBaseFeedback"; }; + const char * getMD5(){ return "3fb824c456a757373a226f6d08071bf0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_move_base_msgs_MoveBaseGoal_h +#define _ROS_move_base_msgs_MoveBaseGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" + +namespace move_base_msgs +{ + + class MoveBaseGoal : public ros::Msg + { + public: + geometry_msgs::PoseStamped target_pose; + + MoveBaseGoal(): + target_pose() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->target_pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->target_pose.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "move_base_msgs/MoveBaseGoal"; }; + const char * getMD5(){ return "257d089627d7eb7136c24d3593d05a16"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/move_base_msgs/MoveBaseResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_move_base_msgs_MoveBaseResult_h +#define _ROS_move_base_msgs_MoveBaseResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace move_base_msgs +{ + + class MoveBaseResult : public ros::Msg + { + public: + + MoveBaseResult() + { + } + + 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 "move_base_msgs/MoveBaseResult"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/AllowedCollisionEntry.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_moveit_msgs_AllowedCollisionEntry_h +#define _ROS_moveit_msgs_AllowedCollisionEntry_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class AllowedCollisionEntry : public ros::Msg + { + public: + uint8_t enabled_length; + bool st_enabled; + bool * enabled; + + AllowedCollisionEntry(): + enabled_length(0), enabled(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = enabled_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < enabled_length; i++){ + union { + bool real; + uint8_t base; + } u_enabledi; + u_enabledi.real = this->enabled[i]; + *(outbuffer + offset + 0) = (u_enabledi.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->enabled[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t enabled_lengthT = *(inbuffer + offset++); + if(enabled_lengthT > enabled_length) + this->enabled = (bool*)realloc(this->enabled, enabled_lengthT * sizeof(bool)); + offset += 3; + enabled_length = enabled_lengthT; + for( uint8_t i = 0; i < enabled_length; i++){ + union { + bool real; + uint8_t base; + } u_st_enabled; + u_st_enabled.base = 0; + u_st_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_enabled = u_st_enabled.real; + offset += sizeof(this->st_enabled); + memcpy( &(this->enabled[i]), &(this->st_enabled), sizeof(bool)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/AllowedCollisionEntry"; }; + const char * getMD5(){ return "90d1ae1850840724bb043562fe3285fc"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/AllowedCollisionMatrix.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,156 @@ +#ifndef _ROS_moveit_msgs_AllowedCollisionMatrix_h +#define _ROS_moveit_msgs_AllowedCollisionMatrix_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/AllowedCollisionEntry.h" + +namespace moveit_msgs +{ + + class AllowedCollisionMatrix : public ros::Msg + { + public: + uint8_t entry_names_length; + char* st_entry_names; + char* * entry_names; + uint8_t entry_values_length; + moveit_msgs::AllowedCollisionEntry st_entry_values; + moveit_msgs::AllowedCollisionEntry * entry_values; + uint8_t default_entry_names_length; + char* st_default_entry_names; + char* * default_entry_names; + uint8_t default_entry_values_length; + bool st_default_entry_values; + bool * default_entry_values; + + AllowedCollisionMatrix(): + entry_names_length(0), entry_names(NULL), + entry_values_length(0), entry_values(NULL), + default_entry_names_length(0), default_entry_names(NULL), + default_entry_values_length(0), default_entry_values(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = entry_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < entry_names_length; i++){ + uint32_t length_entry_namesi = strlen(this->entry_names[i]); + memcpy(outbuffer + offset, &length_entry_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->entry_names[i], length_entry_namesi); + offset += length_entry_namesi; + } + *(outbuffer + offset++) = entry_values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < entry_values_length; i++){ + offset += this->entry_values[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = default_entry_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < default_entry_names_length; i++){ + uint32_t length_default_entry_namesi = strlen(this->default_entry_names[i]); + memcpy(outbuffer + offset, &length_default_entry_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->default_entry_names[i], length_default_entry_namesi); + offset += length_default_entry_namesi; + } + *(outbuffer + offset++) = default_entry_values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < default_entry_values_length; i++){ + union { + bool real; + uint8_t base; + } u_default_entry_valuesi; + u_default_entry_valuesi.real = this->default_entry_values[i]; + *(outbuffer + offset + 0) = (u_default_entry_valuesi.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->default_entry_values[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t entry_names_lengthT = *(inbuffer + offset++); + if(entry_names_lengthT > entry_names_length) + this->entry_names = (char**)realloc(this->entry_names, entry_names_lengthT * sizeof(char*)); + offset += 3; + entry_names_length = entry_names_lengthT; + for( uint8_t i = 0; i < entry_names_length; i++){ + uint32_t length_st_entry_names; + memcpy(&length_st_entry_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_entry_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_entry_names-1]=0; + this->st_entry_names = (char *)(inbuffer + offset-1); + offset += length_st_entry_names; + memcpy( &(this->entry_names[i]), &(this->st_entry_names), sizeof(char*)); + } + uint8_t entry_values_lengthT = *(inbuffer + offset++); + if(entry_values_lengthT > entry_values_length) + this->entry_values = (moveit_msgs::AllowedCollisionEntry*)realloc(this->entry_values, entry_values_lengthT * sizeof(moveit_msgs::AllowedCollisionEntry)); + offset += 3; + entry_values_length = entry_values_lengthT; + for( uint8_t i = 0; i < entry_values_length; i++){ + offset += this->st_entry_values.deserialize(inbuffer + offset); + memcpy( &(this->entry_values[i]), &(this->st_entry_values), sizeof(moveit_msgs::AllowedCollisionEntry)); + } + uint8_t default_entry_names_lengthT = *(inbuffer + offset++); + if(default_entry_names_lengthT > default_entry_names_length) + this->default_entry_names = (char**)realloc(this->default_entry_names, default_entry_names_lengthT * sizeof(char*)); + offset += 3; + default_entry_names_length = default_entry_names_lengthT; + for( uint8_t i = 0; i < default_entry_names_length; i++){ + uint32_t length_st_default_entry_names; + memcpy(&length_st_default_entry_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_default_entry_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_default_entry_names-1]=0; + this->st_default_entry_names = (char *)(inbuffer + offset-1); + offset += length_st_default_entry_names; + memcpy( &(this->default_entry_names[i]), &(this->st_default_entry_names), sizeof(char*)); + } + uint8_t default_entry_values_lengthT = *(inbuffer + offset++); + if(default_entry_values_lengthT > default_entry_values_length) + this->default_entry_values = (bool*)realloc(this->default_entry_values, default_entry_values_lengthT * sizeof(bool)); + offset += 3; + default_entry_values_length = default_entry_values_lengthT; + for( uint8_t i = 0; i < default_entry_values_length; i++){ + union { + bool real; + uint8_t base; + } u_st_default_entry_values; + u_st_default_entry_values.base = 0; + u_st_default_entry_values.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_default_entry_values = u_st_default_entry_values.real; + offset += sizeof(this->st_default_entry_values); + memcpy( &(this->default_entry_values[i]), &(this->st_default_entry_values), sizeof(bool)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/AllowedCollisionMatrix"; }; + const char * getMD5(){ return "aedce13587eef0d79165a075659c1879"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/AttachedCollisionObject.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,100 @@ +#ifndef _ROS_moveit_msgs_AttachedCollisionObject_h +#define _ROS_moveit_msgs_AttachedCollisionObject_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/CollisionObject.h" +#include "trajectory_msgs/JointTrajectory.h" + +namespace moveit_msgs +{ + + class AttachedCollisionObject : public ros::Msg + { + public: + const char* link_name; + moveit_msgs::CollisionObject object; + uint8_t touch_links_length; + char* st_touch_links; + char* * touch_links; + trajectory_msgs::JointTrajectory detach_posture; + float weight; + + AttachedCollisionObject(): + link_name(""), + object(), + touch_links_length(0), touch_links(NULL), + detach_posture(), + weight(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += this->object.serialize(outbuffer + offset); + *(outbuffer + offset++) = touch_links_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < touch_links_length; i++){ + uint32_t length_touch_linksi = strlen(this->touch_links[i]); + memcpy(outbuffer + offset, &length_touch_linksi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->touch_links[i], length_touch_linksi); + offset += length_touch_linksi; + } + offset += this->detach_posture.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->weight); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += this->object.deserialize(inbuffer + offset); + uint8_t touch_links_lengthT = *(inbuffer + offset++); + if(touch_links_lengthT > touch_links_length) + this->touch_links = (char**)realloc(this->touch_links, touch_links_lengthT * sizeof(char*)); + offset += 3; + touch_links_length = touch_links_lengthT; + for( uint8_t i = 0; i < touch_links_length; i++){ + uint32_t length_st_touch_links; + memcpy(&length_st_touch_links, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_touch_links; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_touch_links-1]=0; + this->st_touch_links = (char *)(inbuffer + offset-1); + offset += length_st_touch_links; + memcpy( &(this->touch_links[i]), &(this->st_touch_links), sizeof(char*)); + } + offset += this->detach_posture.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); + return offset; + } + + const char * getType(){ return "moveit_msgs/AttachedCollisionObject"; }; + const char * getMD5(){ return "3ceac60b21e85bbd6c5b0ab9d476b752"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/BoundingVolume.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,121 @@ +#ifndef _ROS_moveit_msgs_BoundingVolume_h +#define _ROS_moveit_msgs_BoundingVolume_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "shape_msgs/SolidPrimitive.h" +#include "geometry_msgs/Pose.h" +#include "shape_msgs/Mesh.h" + +namespace moveit_msgs +{ + + class BoundingVolume : public ros::Msg + { + public: + uint8_t primitives_length; + shape_msgs::SolidPrimitive st_primitives; + shape_msgs::SolidPrimitive * primitives; + uint8_t primitive_poses_length; + geometry_msgs::Pose st_primitive_poses; + geometry_msgs::Pose * primitive_poses; + uint8_t meshes_length; + shape_msgs::Mesh st_meshes; + shape_msgs::Mesh * meshes; + uint8_t mesh_poses_length; + geometry_msgs::Pose st_mesh_poses; + geometry_msgs::Pose * mesh_poses; + + BoundingVolume(): + primitives_length(0), primitives(NULL), + primitive_poses_length(0), primitive_poses(NULL), + meshes_length(0), meshes(NULL), + mesh_poses_length(0), mesh_poses(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = primitives_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < primitives_length; i++){ + offset += this->primitives[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = primitive_poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < primitive_poses_length; i++){ + offset += this->primitive_poses[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = meshes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->meshes[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = mesh_poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < mesh_poses_length; i++){ + offset += this->mesh_poses[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t primitives_lengthT = *(inbuffer + offset++); + if(primitives_lengthT > primitives_length) + this->primitives = (shape_msgs::SolidPrimitive*)realloc(this->primitives, primitives_lengthT * sizeof(shape_msgs::SolidPrimitive)); + offset += 3; + primitives_length = primitives_lengthT; + for( uint8_t i = 0; i < primitives_length; i++){ + offset += this->st_primitives.deserialize(inbuffer + offset); + memcpy( &(this->primitives[i]), &(this->st_primitives), sizeof(shape_msgs::SolidPrimitive)); + } + uint8_t primitive_poses_lengthT = *(inbuffer + offset++); + if(primitive_poses_lengthT > primitive_poses_length) + this->primitive_poses = (geometry_msgs::Pose*)realloc(this->primitive_poses, primitive_poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + primitive_poses_length = primitive_poses_lengthT; + for( uint8_t i = 0; i < primitive_poses_length; i++){ + offset += this->st_primitive_poses.deserialize(inbuffer + offset); + memcpy( &(this->primitive_poses[i]), &(this->st_primitive_poses), sizeof(geometry_msgs::Pose)); + } + uint8_t meshes_lengthT = *(inbuffer + offset++); + if(meshes_lengthT > meshes_length) + this->meshes = (shape_msgs::Mesh*)realloc(this->meshes, meshes_lengthT * sizeof(shape_msgs::Mesh)); + offset += 3; + meshes_length = meshes_lengthT; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->st_meshes.deserialize(inbuffer + offset); + memcpy( &(this->meshes[i]), &(this->st_meshes), sizeof(shape_msgs::Mesh)); + } + uint8_t mesh_poses_lengthT = *(inbuffer + offset++); + if(mesh_poses_lengthT > mesh_poses_length) + this->mesh_poses = (geometry_msgs::Pose*)realloc(this->mesh_poses, mesh_poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + mesh_poses_length = mesh_poses_lengthT; + for( uint8_t i = 0; i < mesh_poses_length; i++){ + offset += this->st_mesh_poses.deserialize(inbuffer + offset); + memcpy( &(this->mesh_poses[i]), &(this->st_mesh_poses), sizeof(geometry_msgs::Pose)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/BoundingVolume"; }; + const char * getMD5(){ return "22db94010f39e9198032cb4a1aeda26e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/CollisionObject.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,209 @@ +#ifndef _ROS_moveit_msgs_CollisionObject_h +#define _ROS_moveit_msgs_CollisionObject_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "object_recognition_msgs/ObjectType.h" +#include "shape_msgs/SolidPrimitive.h" +#include "geometry_msgs/Pose.h" +#include "shape_msgs/Mesh.h" +#include "shape_msgs/Plane.h" + +namespace moveit_msgs +{ + + class CollisionObject : public ros::Msg + { + public: + std_msgs::Header header; + const char* id; + object_recognition_msgs::ObjectType type; + uint8_t primitives_length; + shape_msgs::SolidPrimitive st_primitives; + shape_msgs::SolidPrimitive * primitives; + uint8_t primitive_poses_length; + geometry_msgs::Pose st_primitive_poses; + geometry_msgs::Pose * primitive_poses; + uint8_t meshes_length; + shape_msgs::Mesh st_meshes; + shape_msgs::Mesh * meshes; + uint8_t mesh_poses_length; + geometry_msgs::Pose st_mesh_poses; + geometry_msgs::Pose * mesh_poses; + uint8_t planes_length; + shape_msgs::Plane st_planes; + shape_msgs::Plane * planes; + uint8_t plane_poses_length; + geometry_msgs::Pose st_plane_poses; + geometry_msgs::Pose * plane_poses; + int8_t operation; + enum { ADD = 0 }; + enum { REMOVE = 1 }; + enum { APPEND = 2 }; + enum { MOVE = 3 }; + + CollisionObject(): + header(), + id(""), + type(), + primitives_length(0), primitives(NULL), + primitive_poses_length(0), primitive_poses(NULL), + meshes_length(0), meshes(NULL), + mesh_poses_length(0), mesh_poses(NULL), + planes_length(0), planes(NULL), + plane_poses_length(0), plane_poses(NULL), + operation(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->type.serialize(outbuffer + offset); + *(outbuffer + offset++) = primitives_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < primitives_length; i++){ + offset += this->primitives[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = primitive_poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < primitive_poses_length; i++){ + offset += this->primitive_poses[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = meshes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->meshes[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = mesh_poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < mesh_poses_length; i++){ + offset += this->mesh_poses[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = planes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < planes_length; i++){ + offset += this->planes[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = plane_poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < plane_poses_length; i++){ + offset += this->plane_poses[i].serialize(outbuffer + offset); + } + union { + int8_t real; + uint8_t base; + } u_operation; + u_operation.real = this->operation; + *(outbuffer + offset + 0) = (u_operation.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->operation); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->type.deserialize(inbuffer + offset); + uint8_t primitives_lengthT = *(inbuffer + offset++); + if(primitives_lengthT > primitives_length) + this->primitives = (shape_msgs::SolidPrimitive*)realloc(this->primitives, primitives_lengthT * sizeof(shape_msgs::SolidPrimitive)); + offset += 3; + primitives_length = primitives_lengthT; + for( uint8_t i = 0; i < primitives_length; i++){ + offset += this->st_primitives.deserialize(inbuffer + offset); + memcpy( &(this->primitives[i]), &(this->st_primitives), sizeof(shape_msgs::SolidPrimitive)); + } + uint8_t primitive_poses_lengthT = *(inbuffer + offset++); + if(primitive_poses_lengthT > primitive_poses_length) + this->primitive_poses = (geometry_msgs::Pose*)realloc(this->primitive_poses, primitive_poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + primitive_poses_length = primitive_poses_lengthT; + for( uint8_t i = 0; i < primitive_poses_length; i++){ + offset += this->st_primitive_poses.deserialize(inbuffer + offset); + memcpy( &(this->primitive_poses[i]), &(this->st_primitive_poses), sizeof(geometry_msgs::Pose)); + } + uint8_t meshes_lengthT = *(inbuffer + offset++); + if(meshes_lengthT > meshes_length) + this->meshes = (shape_msgs::Mesh*)realloc(this->meshes, meshes_lengthT * sizeof(shape_msgs::Mesh)); + offset += 3; + meshes_length = meshes_lengthT; + for( uint8_t i = 0; i < meshes_length; i++){ + offset += this->st_meshes.deserialize(inbuffer + offset); + memcpy( &(this->meshes[i]), &(this->st_meshes), sizeof(shape_msgs::Mesh)); + } + uint8_t mesh_poses_lengthT = *(inbuffer + offset++); + if(mesh_poses_lengthT > mesh_poses_length) + this->mesh_poses = (geometry_msgs::Pose*)realloc(this->mesh_poses, mesh_poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + mesh_poses_length = mesh_poses_lengthT; + for( uint8_t i = 0; i < mesh_poses_length; i++){ + offset += this->st_mesh_poses.deserialize(inbuffer + offset); + memcpy( &(this->mesh_poses[i]), &(this->st_mesh_poses), sizeof(geometry_msgs::Pose)); + } + uint8_t planes_lengthT = *(inbuffer + offset++); + if(planes_lengthT > planes_length) + this->planes = (shape_msgs::Plane*)realloc(this->planes, planes_lengthT * sizeof(shape_msgs::Plane)); + offset += 3; + planes_length = planes_lengthT; + for( uint8_t i = 0; i < planes_length; i++){ + offset += this->st_planes.deserialize(inbuffer + offset); + memcpy( &(this->planes[i]), &(this->st_planes), sizeof(shape_msgs::Plane)); + } + uint8_t plane_poses_lengthT = *(inbuffer + offset++); + if(plane_poses_lengthT > plane_poses_length) + this->plane_poses = (geometry_msgs::Pose*)realloc(this->plane_poses, plane_poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + plane_poses_length = plane_poses_lengthT; + for( uint8_t i = 0; i < plane_poses_length; i++){ + offset += this->st_plane_poses.deserialize(inbuffer + offset); + memcpy( &(this->plane_poses[i]), &(this->st_plane_poses), sizeof(geometry_msgs::Pose)); + } + union { + int8_t real; + uint8_t base; + } u_operation; + u_operation.base = 0; + u_operation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->operation = u_operation.real; + offset += sizeof(this->operation); + return offset; + } + + const char * getType(){ return "moveit_msgs/CollisionObject"; }; + const char * getMD5(){ return "568a161b26dc46c54a5a07621ce82cf3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/ConstraintEvalResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_moveit_msgs_ConstraintEvalResult_h +#define _ROS_moveit_msgs_ConstraintEvalResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class ConstraintEvalResult : public ros::Msg + { + public: + bool result; + float distance; + + ConstraintEvalResult(): + result(0), + distance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_result; + u_result.real = this->result; + *(outbuffer + offset + 0) = (u_result.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->result); + offset += serializeAvrFloat64(outbuffer + offset, this->distance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_result; + u_result.base = 0; + u_result.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->result = u_result.real; + offset += sizeof(this->result); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->distance)); + return offset; + } + + const char * getType(){ return "moveit_msgs/ConstraintEvalResult"; }; + const char * getMD5(){ return "093643083d24f6488cb5a868bd47c090"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/Constraints.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_moveit_msgs_Constraints_h +#define _ROS_moveit_msgs_Constraints_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/JointConstraint.h" +#include "moveit_msgs/PositionConstraint.h" +#include "moveit_msgs/OrientationConstraint.h" +#include "moveit_msgs/VisibilityConstraint.h" + +namespace moveit_msgs +{ + + class Constraints : public ros::Msg + { + public: + const char* name; + uint8_t joint_constraints_length; + moveit_msgs::JointConstraint st_joint_constraints; + moveit_msgs::JointConstraint * joint_constraints; + uint8_t position_constraints_length; + moveit_msgs::PositionConstraint st_position_constraints; + moveit_msgs::PositionConstraint * position_constraints; + uint8_t orientation_constraints_length; + moveit_msgs::OrientationConstraint st_orientation_constraints; + moveit_msgs::OrientationConstraint * orientation_constraints; + uint8_t visibility_constraints_length; + moveit_msgs::VisibilityConstraint st_visibility_constraints; + moveit_msgs::VisibilityConstraint * visibility_constraints; + + Constraints(): + name(""), + joint_constraints_length(0), joint_constraints(NULL), + position_constraints_length(0), position_constraints(NULL), + orientation_constraints_length(0), orientation_constraints(NULL), + visibility_constraints_length(0), visibility_constraints(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset++) = joint_constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_constraints_length; i++){ + offset += this->joint_constraints[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = position_constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < position_constraints_length; i++){ + offset += this->position_constraints[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = orientation_constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < orientation_constraints_length; i++){ + offset += this->orientation_constraints[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = visibility_constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < visibility_constraints_length; i++){ + offset += this->visibility_constraints[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint8_t joint_constraints_lengthT = *(inbuffer + offset++); + if(joint_constraints_lengthT > joint_constraints_length) + this->joint_constraints = (moveit_msgs::JointConstraint*)realloc(this->joint_constraints, joint_constraints_lengthT * sizeof(moveit_msgs::JointConstraint)); + offset += 3; + joint_constraints_length = joint_constraints_lengthT; + for( uint8_t i = 0; i < joint_constraints_length; i++){ + offset += this->st_joint_constraints.deserialize(inbuffer + offset); + memcpy( &(this->joint_constraints[i]), &(this->st_joint_constraints), sizeof(moveit_msgs::JointConstraint)); + } + uint8_t position_constraints_lengthT = *(inbuffer + offset++); + if(position_constraints_lengthT > position_constraints_length) + this->position_constraints = (moveit_msgs::PositionConstraint*)realloc(this->position_constraints, position_constraints_lengthT * sizeof(moveit_msgs::PositionConstraint)); + offset += 3; + position_constraints_length = position_constraints_lengthT; + for( uint8_t i = 0; i < position_constraints_length; i++){ + offset += this->st_position_constraints.deserialize(inbuffer + offset); + memcpy( &(this->position_constraints[i]), &(this->st_position_constraints), sizeof(moveit_msgs::PositionConstraint)); + } + uint8_t orientation_constraints_lengthT = *(inbuffer + offset++); + if(orientation_constraints_lengthT > orientation_constraints_length) + this->orientation_constraints = (moveit_msgs::OrientationConstraint*)realloc(this->orientation_constraints, orientation_constraints_lengthT * sizeof(moveit_msgs::OrientationConstraint)); + offset += 3; + orientation_constraints_length = orientation_constraints_lengthT; + for( uint8_t i = 0; i < orientation_constraints_length; i++){ + offset += this->st_orientation_constraints.deserialize(inbuffer + offset); + memcpy( &(this->orientation_constraints[i]), &(this->st_orientation_constraints), sizeof(moveit_msgs::OrientationConstraint)); + } + uint8_t visibility_constraints_lengthT = *(inbuffer + offset++); + if(visibility_constraints_lengthT > visibility_constraints_length) + this->visibility_constraints = (moveit_msgs::VisibilityConstraint*)realloc(this->visibility_constraints, visibility_constraints_lengthT * sizeof(moveit_msgs::VisibilityConstraint)); + offset += 3; + visibility_constraints_length = visibility_constraints_lengthT; + for( uint8_t i = 0; i < visibility_constraints_length; i++){ + offset += this->st_visibility_constraints.deserialize(inbuffer + offset); + memcpy( &(this->visibility_constraints[i]), &(this->st_visibility_constraints), sizeof(moveit_msgs::VisibilityConstraint)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/Constraints"; }; + const char * getMD5(){ return "8d5ce8d34ef26c65fb5d43c9e99bf6e0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/ContactInformation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,116 @@ +#ifndef _ROS_moveit_msgs_ContactInformation_h +#define _ROS_moveit_msgs_ContactInformation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" +#include "geometry_msgs/Vector3.h" + +namespace moveit_msgs +{ + + class ContactInformation : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Point position; + geometry_msgs::Vector3 normal; + float depth; + const char* contact_body_1; + uint32_t body_type_1; + const char* contact_body_2; + uint32_t body_type_2; + enum { ROBOT_LINK = 0 }; + enum { WORLD_OBJECT = 1 }; + enum { ROBOT_ATTACHED = 2 }; + + ContactInformation(): + header(), + position(), + normal(), + depth(0), + contact_body_1(""), + body_type_1(0), + contact_body_2(""), + body_type_2(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->position.serialize(outbuffer + offset); + offset += this->normal.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->depth); + uint32_t length_contact_body_1 = strlen(this->contact_body_1); + memcpy(outbuffer + offset, &length_contact_body_1, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->contact_body_1, length_contact_body_1); + offset += length_contact_body_1; + *(outbuffer + offset + 0) = (this->body_type_1 >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->body_type_1 >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->body_type_1 >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->body_type_1 >> (8 * 3)) & 0xFF; + offset += sizeof(this->body_type_1); + uint32_t length_contact_body_2 = strlen(this->contact_body_2); + memcpy(outbuffer + offset, &length_contact_body_2, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->contact_body_2, length_contact_body_2); + offset += length_contact_body_2; + *(outbuffer + offset + 0) = (this->body_type_2 >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->body_type_2 >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->body_type_2 >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->body_type_2 >> (8 * 3)) & 0xFF; + offset += sizeof(this->body_type_2); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->position.deserialize(inbuffer + offset); + offset += this->normal.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->depth)); + uint32_t length_contact_body_1; + memcpy(&length_contact_body_1, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_contact_body_1; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_contact_body_1-1]=0; + this->contact_body_1 = (char *)(inbuffer + offset-1); + offset += length_contact_body_1; + this->body_type_1 = ((uint32_t) (*(inbuffer + offset))); + this->body_type_1 |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->body_type_1 |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->body_type_1 |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->body_type_1); + uint32_t length_contact_body_2; + memcpy(&length_contact_body_2, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_contact_body_2; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_contact_body_2-1]=0; + this->contact_body_2 = (char *)(inbuffer + offset-1); + offset += length_contact_body_2; + this->body_type_2 = ((uint32_t) (*(inbuffer + offset))); + this->body_type_2 |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->body_type_2 |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->body_type_2 |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->body_type_2); + return offset; + } + + const char * getType(){ return "moveit_msgs/ContactInformation"; }; + const char * getMD5(){ return "116228ca08b0c286ec5ca32a50fdc17b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/CostSource.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,51 @@ +#ifndef _ROS_moveit_msgs_CostSource_h +#define _ROS_moveit_msgs_CostSource_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" + +namespace moveit_msgs +{ + + class CostSource : public ros::Msg + { + public: + float cost_density; + geometry_msgs::Vector3 aabb_min; + geometry_msgs::Vector3 aabb_max; + + CostSource(): + cost_density(0), + aabb_min(), + aabb_max() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->cost_density); + offset += this->aabb_min.serialize(outbuffer + offset); + offset += this->aabb_max.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->cost_density)); + offset += this->aabb_min.deserialize(inbuffer + offset); + offset += this->aabb_max.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/CostSource"; }; + const char * getMD5(){ return "abb7e013237dacaaa8b97e704102f908"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/DisplayRobotState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_moveit_msgs_DisplayRobotState_h +#define _ROS_moveit_msgs_DisplayRobotState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/ObjectColor.h" + +namespace moveit_msgs +{ + + class DisplayRobotState : public ros::Msg + { + public: + moveit_msgs::RobotState state; + uint8_t highlight_links_length; + moveit_msgs::ObjectColor st_highlight_links; + moveit_msgs::ObjectColor * highlight_links; + + DisplayRobotState(): + state(), + highlight_links_length(0), highlight_links(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->state.serialize(outbuffer + offset); + *(outbuffer + offset++) = highlight_links_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < highlight_links_length; i++){ + offset += this->highlight_links[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->state.deserialize(inbuffer + offset); + uint8_t highlight_links_lengthT = *(inbuffer + offset++); + if(highlight_links_lengthT > highlight_links_length) + this->highlight_links = (moveit_msgs::ObjectColor*)realloc(this->highlight_links, highlight_links_lengthT * sizeof(moveit_msgs::ObjectColor)); + offset += 3; + highlight_links_length = highlight_links_lengthT; + for( uint8_t i = 0; i < highlight_links_length; i++){ + offset += this->st_highlight_links.deserialize(inbuffer + offset); + memcpy( &(this->highlight_links[i]), &(this->st_highlight_links), sizeof(moveit_msgs::ObjectColor)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/DisplayRobotState"; }; + const char * getMD5(){ return "6a3bab3a33a8c47aee24481a455a21aa"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/DisplayTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_moveit_msgs_DisplayTrajectory_h +#define _ROS_moveit_msgs_DisplayTrajectory_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/RobotState.h" + +namespace moveit_msgs +{ + + class DisplayTrajectory : public ros::Msg + { + public: + const char* model_id; + uint8_t trajectory_length; + moveit_msgs::RobotTrajectory st_trajectory; + moveit_msgs::RobotTrajectory * trajectory; + moveit_msgs::RobotState trajectory_start; + + DisplayTrajectory(): + model_id(""), + trajectory_length(0), trajectory(NULL), + trajectory_start() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_model_id = strlen(this->model_id); + memcpy(outbuffer + offset, &length_model_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->model_id, length_model_id); + offset += length_model_id; + *(outbuffer + offset++) = trajectory_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_length; i++){ + offset += this->trajectory[i].serialize(outbuffer + offset); + } + offset += this->trajectory_start.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_model_id; + memcpy(&length_model_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_model_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_model_id-1]=0; + this->model_id = (char *)(inbuffer + offset-1); + offset += length_model_id; + uint8_t trajectory_lengthT = *(inbuffer + offset++); + if(trajectory_lengthT > trajectory_length) + this->trajectory = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory, trajectory_lengthT * sizeof(moveit_msgs::RobotTrajectory)); + offset += 3; + trajectory_length = trajectory_lengthT; + for( uint8_t i = 0; i < trajectory_length; i++){ + offset += this->st_trajectory.deserialize(inbuffer + offset); + memcpy( &(this->trajectory[i]), &(this->st_trajectory), sizeof(moveit_msgs::RobotTrajectory)); + } + offset += this->trajectory_start.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/DisplayTrajectory"; }; + const char * getMD5(){ return "c3c039261ab9e8a11457dac56b6316c8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/ExecuteKnownTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,98 @@ +#ifndef _ROS_SERVICE_ExecuteKnownTrajectory_h +#define _ROS_SERVICE_ExecuteKnownTrajectory_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/RobotTrajectory.h" + +namespace moveit_msgs +{ + +static const char EXECUTEKNOWNTRAJECTORY[] = "moveit_msgs/ExecuteKnownTrajectory"; + + class ExecuteKnownTrajectoryRequest : public ros::Msg + { + public: + moveit_msgs::RobotTrajectory trajectory; + bool wait_for_execution; + + ExecuteKnownTrajectoryRequest(): + trajectory(), + wait_for_execution(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->trajectory.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_wait_for_execution; + u_wait_for_execution.real = this->wait_for_execution; + *(outbuffer + offset + 0) = (u_wait_for_execution.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->wait_for_execution); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->trajectory.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_wait_for_execution; + u_wait_for_execution.base = 0; + u_wait_for_execution.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->wait_for_execution = u_wait_for_execution.real; + offset += sizeof(this->wait_for_execution); + return offset; + } + + const char * getType(){ return EXECUTEKNOWNTRAJECTORY; }; + const char * getMD5(){ return "2a3d2a0b337c6a27da4468bb351928e5"; }; + + }; + + class ExecuteKnownTrajectoryResponse : public ros::Msg + { + public: + moveit_msgs::MoveItErrorCodes error_code; + + ExecuteKnownTrajectoryResponse(): + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return EXECUTEKNOWNTRAJECTORY; }; + const char * getMD5(){ return "1f7ab918f5d0c5312f25263d3d688122"; }; + + }; + + class ExecuteKnownTrajectory { + public: + typedef ExecuteKnownTrajectoryRequest Request; + typedef ExecuteKnownTrajectoryResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetCartesianPath.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,182 @@ +#ifndef _ROS_SERVICE_GetCartesianPath_h +#define _ROS_SERVICE_GetCartesianPath_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "geometry_msgs/Pose.h" +#include "moveit_msgs/Constraints.h" + +namespace moveit_msgs +{ + +static const char GETCARTESIANPATH[] = "moveit_msgs/GetCartesianPath"; + + class GetCartesianPathRequest : public ros::Msg + { + public: + std_msgs::Header header; + moveit_msgs::RobotState start_state; + const char* group_name; + const char* link_name; + uint8_t waypoints_length; + geometry_msgs::Pose st_waypoints; + geometry_msgs::Pose * waypoints; + float max_step; + float jump_threshold; + bool avoid_collisions; + moveit_msgs::Constraints path_constraints; + + GetCartesianPathRequest(): + header(), + start_state(), + group_name(""), + link_name(""), + waypoints_length(0), waypoints(NULL), + max_step(0), + jump_threshold(0), + avoid_collisions(0), + path_constraints() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->start_state.serialize(outbuffer + offset); + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + *(outbuffer + offset++) = waypoints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < waypoints_length; i++){ + offset += this->waypoints[i].serialize(outbuffer + offset); + } + offset += serializeAvrFloat64(outbuffer + offset, this->max_step); + offset += serializeAvrFloat64(outbuffer + offset, this->jump_threshold); + union { + bool real; + uint8_t base; + } u_avoid_collisions; + u_avoid_collisions.real = this->avoid_collisions; + *(outbuffer + offset + 0) = (u_avoid_collisions.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->avoid_collisions); + offset += this->path_constraints.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->start_state.deserialize(inbuffer + offset); + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + uint8_t waypoints_lengthT = *(inbuffer + offset++); + if(waypoints_lengthT > waypoints_length) + this->waypoints = (geometry_msgs::Pose*)realloc(this->waypoints, waypoints_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + waypoints_length = waypoints_lengthT; + for( uint8_t i = 0; i < waypoints_length; i++){ + offset += this->st_waypoints.deserialize(inbuffer + offset); + memcpy( &(this->waypoints[i]), &(this->st_waypoints), sizeof(geometry_msgs::Pose)); + } + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_step)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->jump_threshold)); + union { + bool real; + uint8_t base; + } u_avoid_collisions; + u_avoid_collisions.base = 0; + u_avoid_collisions.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->avoid_collisions = u_avoid_collisions.real; + offset += sizeof(this->avoid_collisions); + offset += this->path_constraints.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCARTESIANPATH; }; + const char * getMD5(){ return "b37c16ad7ed838d811a270a8054276b6"; }; + + }; + + class GetCartesianPathResponse : public ros::Msg + { + public: + moveit_msgs::RobotState start_state; + moveit_msgs::RobotTrajectory solution; + float fraction; + moveit_msgs::MoveItErrorCodes error_code; + + GetCartesianPathResponse(): + start_state(), + solution(), + fraction(0), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->start_state.serialize(outbuffer + offset); + offset += this->solution.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->fraction); + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->start_state.deserialize(inbuffer + offset); + offset += this->solution.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->fraction)); + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCARTESIANPATH; }; + const char * getMD5(){ return "45414110461a45eb0e273e013924ce59"; }; + + }; + + class GetCartesianPath { + public: + typedef GetCartesianPathRequest Request; + typedef GetCartesianPathResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetConstraintAwarePositionIK.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,91 @@ +#ifndef _ROS_SERVICE_GetConstraintAwarePositionIK_h +#define _ROS_SERVICE_GetConstraintAwarePositionIK_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/PositionIKRequest.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/Constraints.h" + +namespace moveit_msgs +{ + +static const char GETCONSTRAINTAWAREPOSITIONIK[] = "moveit_msgs/GetConstraintAwarePositionIK"; + + class GetConstraintAwarePositionIKRequest : public ros::Msg + { + public: + moveit_msgs::PositionIKRequest ik_request; + moveit_msgs::Constraints constraints; + + GetConstraintAwarePositionIKRequest(): + ik_request(), + constraints() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->ik_request.serialize(outbuffer + offset); + offset += this->constraints.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->ik_request.deserialize(inbuffer + offset); + offset += this->constraints.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; }; + const char * getMD5(){ return "7397fbef2589fd33df21251c96c43f11"; }; + + }; + + class GetConstraintAwarePositionIKResponse : public ros::Msg + { + public: + moveit_msgs::RobotState solution; + moveit_msgs::MoveItErrorCodes error_code; + + GetConstraintAwarePositionIKResponse(): + solution(), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->solution.serialize(outbuffer + offset); + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->solution.deserialize(inbuffer + offset); + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; }; + const char * getMD5(){ return "ad50fe5fa0ddb482909be313121ea148"; }; + + }; + + class GetConstraintAwarePositionIK { + public: + typedef GetConstraintAwarePositionIKRequest Request; + typedef GetConstraintAwarePositionIKResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetKinematicSolverInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_GetKinematicSolverInfo_h +#define _ROS_SERVICE_GetKinematicSolverInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/KinematicSolverInfo.h" + +namespace moveit_msgs +{ + +static const char GETKINEMATICSOLVERINFO[] = "moveit_msgs/GetKinematicSolverInfo"; + + class GetKinematicSolverInfoRequest : public ros::Msg + { + public: + + GetKinematicSolverInfoRequest() + { + } + + 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 GETKINEMATICSOLVERINFO; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetKinematicSolverInfoResponse : public ros::Msg + { + public: + moveit_msgs::KinematicSolverInfo kinematic_solver_info; + + GetKinematicSolverInfoResponse(): + kinematic_solver_info() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->kinematic_solver_info.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->kinematic_solver_info.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETKINEMATICSOLVERINFO; }; + const char * getMD5(){ return "9b591d98efeb66095c1b33a70221cab5"; }; + + }; + + class GetKinematicSolverInfo { + public: + typedef GetKinematicSolverInfoRequest Request; + typedef GetKinematicSolverInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetMotionPlan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_SERVICE_GetMotionPlan_h +#define _ROS_SERVICE_GetMotionPlan_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MotionPlanRequest.h" +#include "moveit_msgs/MotionPlanResponse.h" + +namespace moveit_msgs +{ + +static const char GETMOTIONPLAN[] = "moveit_msgs/GetMotionPlan"; + + class GetMotionPlanRequest : public ros::Msg + { + public: + moveit_msgs::MotionPlanRequest motion_plan_request; + + GetMotionPlanRequest(): + motion_plan_request() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->motion_plan_request.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->motion_plan_request.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMOTIONPLAN; }; + const char * getMD5(){ return "fde307a5260284ee255be16f0cdf01d0"; }; + + }; + + class GetMotionPlanResponse : public ros::Msg + { + public: + moveit_msgs::MotionPlanResponse motion_plan_response; + + GetMotionPlanResponse(): + motion_plan_response() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->motion_plan_response.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->motion_plan_response.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMOTIONPLAN; }; + const char * getMD5(){ return "37fe7e8f0d4dfa55ccfa53d63c86ae15"; }; + + }; + + class GetMotionPlan { + public: + typedef GetMotionPlanRequest Request; + typedef GetMotionPlanResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetPlanningScene.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_SERVICE_GetPlanningScene_h +#define _ROS_SERVICE_GetPlanningScene_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PlanningScene.h" +#include "moveit_msgs/PlanningSceneComponents.h" + +namespace moveit_msgs +{ + +static const char GETPLANNINGSCENE[] = "moveit_msgs/GetPlanningScene"; + + class GetPlanningSceneRequest : public ros::Msg + { + public: + moveit_msgs::PlanningSceneComponents components; + + GetPlanningSceneRequest(): + components() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->components.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->components.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPLANNINGSCENE; }; + const char * getMD5(){ return "d81da6c0e5e015646a4efe344f33d7dc"; }; + + }; + + class GetPlanningSceneResponse : public ros::Msg + { + public: + moveit_msgs::PlanningScene scene; + + GetPlanningSceneResponse(): + scene() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->scene.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->scene.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPLANNINGSCENE; }; + const char * getMD5(){ return "7bedc4871b1d0af6ec8b8996db347e7f"; }; + + }; + + class GetPlanningScene { + public: + typedef GetPlanningSceneRequest Request; + typedef GetPlanningSceneResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetPositionFK.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,171 @@ +#ifndef _ROS_SERVICE_GetPositionFK_h +#define _ROS_SERVICE_GetPositionFK_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "geometry_msgs/PoseStamped.h" +#include "std_msgs/Header.h" +#include "moveit_msgs/RobotState.h" + +namespace moveit_msgs +{ + +static const char GETPOSITIONFK[] = "moveit_msgs/GetPositionFK"; + + class GetPositionFKRequest : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t fk_link_names_length; + char* st_fk_link_names; + char* * fk_link_names; + moveit_msgs::RobotState robot_state; + + GetPositionFKRequest(): + header(), + fk_link_names_length(0), fk_link_names(NULL), + robot_state() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = fk_link_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fk_link_names_length; i++){ + uint32_t length_fk_link_namesi = strlen(this->fk_link_names[i]); + memcpy(outbuffer + offset, &length_fk_link_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->fk_link_names[i], length_fk_link_namesi); + offset += length_fk_link_namesi; + } + offset += this->robot_state.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t fk_link_names_lengthT = *(inbuffer + offset++); + if(fk_link_names_lengthT > fk_link_names_length) + this->fk_link_names = (char**)realloc(this->fk_link_names, fk_link_names_lengthT * sizeof(char*)); + offset += 3; + fk_link_names_length = fk_link_names_lengthT; + for( uint8_t i = 0; i < fk_link_names_length; i++){ + uint32_t length_st_fk_link_names; + memcpy(&length_st_fk_link_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_fk_link_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_fk_link_names-1]=0; + this->st_fk_link_names = (char *)(inbuffer + offset-1); + offset += length_st_fk_link_names; + memcpy( &(this->fk_link_names[i]), &(this->st_fk_link_names), sizeof(char*)); + } + offset += this->robot_state.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOSITIONFK; }; + const char * getMD5(){ return "1d1ed72044ed56f6246c31b522781797"; }; + + }; + + class GetPositionFKResponse : public ros::Msg + { + public: + uint8_t pose_stamped_length; + geometry_msgs::PoseStamped st_pose_stamped; + geometry_msgs::PoseStamped * pose_stamped; + uint8_t fk_link_names_length; + char* st_fk_link_names; + char* * fk_link_names; + moveit_msgs::MoveItErrorCodes error_code; + + GetPositionFKResponse(): + pose_stamped_length(0), pose_stamped(NULL), + fk_link_names_length(0), fk_link_names(NULL), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = pose_stamped_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_stamped_length; i++){ + offset += this->pose_stamped[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = fk_link_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fk_link_names_length; i++){ + uint32_t length_fk_link_namesi = strlen(this->fk_link_names[i]); + memcpy(outbuffer + offset, &length_fk_link_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->fk_link_names[i], length_fk_link_namesi); + offset += length_fk_link_namesi; + } + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t pose_stamped_lengthT = *(inbuffer + offset++); + if(pose_stamped_lengthT > pose_stamped_length) + this->pose_stamped = (geometry_msgs::PoseStamped*)realloc(this->pose_stamped, pose_stamped_lengthT * sizeof(geometry_msgs::PoseStamped)); + offset += 3; + pose_stamped_length = pose_stamped_lengthT; + for( uint8_t i = 0; i < pose_stamped_length; i++){ + offset += this->st_pose_stamped.deserialize(inbuffer + offset); + memcpy( &(this->pose_stamped[i]), &(this->st_pose_stamped), sizeof(geometry_msgs::PoseStamped)); + } + uint8_t fk_link_names_lengthT = *(inbuffer + offset++); + if(fk_link_names_lengthT > fk_link_names_length) + this->fk_link_names = (char**)realloc(this->fk_link_names, fk_link_names_lengthT * sizeof(char*)); + offset += 3; + fk_link_names_length = fk_link_names_lengthT; + for( uint8_t i = 0; i < fk_link_names_length; i++){ + uint32_t length_st_fk_link_names; + memcpy(&length_st_fk_link_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_fk_link_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_fk_link_names-1]=0; + this->st_fk_link_names = (char *)(inbuffer + offset-1); + offset += length_st_fk_link_names; + memcpy( &(this->fk_link_names[i]), &(this->st_fk_link_names), sizeof(char*)); + } + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOSITIONFK; }; + const char * getMD5(){ return "297215cf4fdfe0008356995ae621dae6"; }; + + }; + + class GetPositionFK { + public: + typedef GetPositionFKRequest Request; + typedef GetPositionFKResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetPositionIK.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,86 @@ +#ifndef _ROS_SERVICE_GetPositionIK_h +#define _ROS_SERVICE_GetPositionIK_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/PositionIKRequest.h" +#include "moveit_msgs/RobotState.h" + +namespace moveit_msgs +{ + +static const char GETPOSITIONIK[] = "moveit_msgs/GetPositionIK"; + + class GetPositionIKRequest : public ros::Msg + { + public: + moveit_msgs::PositionIKRequest ik_request; + + GetPositionIKRequest(): + ik_request() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->ik_request.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->ik_request.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOSITIONIK; }; + const char * getMD5(){ return "a67dc7e99d15c1dca32a77c22bc2d93b"; }; + + }; + + class GetPositionIKResponse : public ros::Msg + { + public: + moveit_msgs::RobotState solution; + moveit_msgs::MoveItErrorCodes error_code; + + GetPositionIKResponse(): + solution(), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->solution.serialize(outbuffer + offset); + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->solution.deserialize(inbuffer + offset); + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOSITIONIK; }; + const char * getMD5(){ return "ad50fe5fa0ddb482909be313121ea148"; }; + + }; + + class GetPositionIK { + public: + typedef GetPositionIKRequest Request; + typedef GetPositionIKResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetStateValidity.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,177 @@ +#ifndef _ROS_SERVICE_GetStateValidity_h +#define _ROS_SERVICE_GetStateValidity_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/ConstraintEvalResult.h" +#include "moveit_msgs/CostSource.h" +#include "moveit_msgs/ContactInformation.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/Constraints.h" + +namespace moveit_msgs +{ + +static const char GETSTATEVALIDITY[] = "moveit_msgs/GetStateValidity"; + + class GetStateValidityRequest : public ros::Msg + { + public: + moveit_msgs::RobotState robot_state; + const char* group_name; + moveit_msgs::Constraints constraints; + + GetStateValidityRequest(): + robot_state(), + group_name(""), + constraints() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->robot_state.serialize(outbuffer + offset); + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + offset += this->constraints.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->robot_state.deserialize(inbuffer + offset); + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + offset += this->constraints.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETSTATEVALIDITY; }; + const char * getMD5(){ return "b569c609cafad20ba7d0e46e70e7cab1"; }; + + }; + + class GetStateValidityResponse : public ros::Msg + { + public: + bool valid; + uint8_t contacts_length; + moveit_msgs::ContactInformation st_contacts; + moveit_msgs::ContactInformation * contacts; + uint8_t cost_sources_length; + moveit_msgs::CostSource st_cost_sources; + moveit_msgs::CostSource * cost_sources; + uint8_t constraint_result_length; + moveit_msgs::ConstraintEvalResult st_constraint_result; + moveit_msgs::ConstraintEvalResult * constraint_result; + + GetStateValidityResponse(): + valid(0), + contacts_length(0), contacts(NULL), + cost_sources_length(0), cost_sources(NULL), + constraint_result_length(0), constraint_result(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_valid; + u_valid.real = this->valid; + *(outbuffer + offset + 0) = (u_valid.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->valid); + *(outbuffer + offset++) = contacts_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < contacts_length; i++){ + offset += this->contacts[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = cost_sources_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < cost_sources_length; i++){ + offset += this->cost_sources[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = constraint_result_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < constraint_result_length; i++){ + offset += this->constraint_result[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_valid; + u_valid.base = 0; + u_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->valid = u_valid.real; + offset += sizeof(this->valid); + uint8_t contacts_lengthT = *(inbuffer + offset++); + if(contacts_lengthT > contacts_length) + this->contacts = (moveit_msgs::ContactInformation*)realloc(this->contacts, contacts_lengthT * sizeof(moveit_msgs::ContactInformation)); + offset += 3; + contacts_length = contacts_lengthT; + for( uint8_t i = 0; i < contacts_length; i++){ + offset += this->st_contacts.deserialize(inbuffer + offset); + memcpy( &(this->contacts[i]), &(this->st_contacts), sizeof(moveit_msgs::ContactInformation)); + } + uint8_t cost_sources_lengthT = *(inbuffer + offset++); + if(cost_sources_lengthT > cost_sources_length) + this->cost_sources = (moveit_msgs::CostSource*)realloc(this->cost_sources, cost_sources_lengthT * sizeof(moveit_msgs::CostSource)); + offset += 3; + cost_sources_length = cost_sources_lengthT; + for( uint8_t i = 0; i < cost_sources_length; i++){ + offset += this->st_cost_sources.deserialize(inbuffer + offset); + memcpy( &(this->cost_sources[i]), &(this->st_cost_sources), sizeof(moveit_msgs::CostSource)); + } + uint8_t constraint_result_lengthT = *(inbuffer + offset++); + if(constraint_result_lengthT > constraint_result_length) + this->constraint_result = (moveit_msgs::ConstraintEvalResult*)realloc(this->constraint_result, constraint_result_lengthT * sizeof(moveit_msgs::ConstraintEvalResult)); + offset += 3; + constraint_result_length = constraint_result_lengthT; + for( uint8_t i = 0; i < constraint_result_length; i++){ + offset += this->st_constraint_result.deserialize(inbuffer + offset); + memcpy( &(this->constraint_result[i]), &(this->st_constraint_result), sizeof(moveit_msgs::ConstraintEvalResult)); + } + return offset; + } + + const char * getType(){ return GETSTATEVALIDITY; }; + const char * getMD5(){ return "e326fb22b7448f29c0e726d9270d9929"; }; + + }; + + class GetStateValidity { + public: + typedef GetStateValidityRequest Request; + typedef GetStateValidityResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/Grasp.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,140 @@ +#ifndef _ROS_moveit_msgs_Grasp_h +#define _ROS_moveit_msgs_Grasp_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "geometry_msgs/PoseStamped.h" +#include "moveit_msgs/GripperTranslation.h" + +namespace moveit_msgs +{ + + class Grasp : public ros::Msg + { + public: + const char* id; + trajectory_msgs::JointTrajectory pre_grasp_posture; + trajectory_msgs::JointTrajectory grasp_posture; + geometry_msgs::PoseStamped grasp_pose; + float grasp_quality; + moveit_msgs::GripperTranslation pre_grasp_approach; + moveit_msgs::GripperTranslation post_grasp_retreat; + moveit_msgs::GripperTranslation post_place_retreat; + float max_contact_force; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + + Grasp(): + id(""), + pre_grasp_posture(), + grasp_posture(), + grasp_pose(), + grasp_quality(0), + pre_grasp_approach(), + post_grasp_retreat(), + post_place_retreat(), + max_contact_force(0), + allowed_touch_objects_length(0), allowed_touch_objects(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->pre_grasp_posture.serialize(outbuffer + offset); + offset += this->grasp_posture.serialize(outbuffer + offset); + offset += this->grasp_pose.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->grasp_quality); + offset += this->pre_grasp_approach.serialize(outbuffer + offset); + offset += this->post_grasp_retreat.serialize(outbuffer + offset); + offset += this->post_place_retreat.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_max_contact_force; + u_max_contact_force.real = this->max_contact_force; + *(outbuffer + offset + 0) = (u_max_contact_force.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_contact_force.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_contact_force.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_contact_force.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_contact_force); + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->pre_grasp_posture.deserialize(inbuffer + offset); + offset += this->grasp_posture.deserialize(inbuffer + offset); + offset += this->grasp_pose.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->grasp_quality)); + offset += this->pre_grasp_approach.deserialize(inbuffer + offset); + offset += this->post_grasp_retreat.deserialize(inbuffer + offset); + offset += this->post_place_retreat.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_max_contact_force; + u_max_contact_force.base = 0; + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_contact_force.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_contact_force = u_max_contact_force.real; + offset += sizeof(this->max_contact_force); + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/Grasp"; }; + const char * getMD5(){ return "e26c8fb64f589c33c5d5e54bd7b5e4cb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GripperTranslation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,89 @@ +#ifndef _ROS_moveit_msgs_GripperTranslation_h +#define _ROS_moveit_msgs_GripperTranslation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3Stamped.h" + +namespace moveit_msgs +{ + + class GripperTranslation : public ros::Msg + { + public: + geometry_msgs::Vector3Stamped direction; + float desired_distance; + float min_distance; + + GripperTranslation(): + direction(), + desired_distance(0), + min_distance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->direction.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_desired_distance; + u_desired_distance.real = this->desired_distance; + *(outbuffer + offset + 0) = (u_desired_distance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_desired_distance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_desired_distance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_desired_distance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->desired_distance); + union { + float real; + uint32_t base; + } u_min_distance; + u_min_distance.real = this->min_distance; + *(outbuffer + offset + 0) = (u_min_distance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_distance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_distance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_distance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_distance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->direction.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_desired_distance; + u_desired_distance.base = 0; + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_desired_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->desired_distance = u_desired_distance.real; + offset += sizeof(this->desired_distance); + union { + float real; + uint32_t base; + } u_min_distance; + u_min_distance.base = 0; + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_distance = u_min_distance.real; + offset += sizeof(this->min_distance); + return offset; + } + + const char * getType(){ return "moveit_msgs/GripperTranslation"; }; + const char * getMD5(){ return "b53bc0ad0f717cdec3b0e42dec300121"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/JointConstraint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_moveit_msgs_JointConstraint_h +#define _ROS_moveit_msgs_JointConstraint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class JointConstraint : public ros::Msg + { + public: + const char* joint_name; + float position; + float tolerance_above; + float tolerance_below; + float weight; + + JointConstraint(): + joint_name(""), + position(0), + tolerance_above(0), + tolerance_below(0), + weight(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->tolerance_above); + offset += serializeAvrFloat64(outbuffer + offset, this->tolerance_below); + offset += serializeAvrFloat64(outbuffer + offset, this->weight); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->tolerance_above)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->tolerance_below)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); + return offset; + } + + const char * getType(){ return "moveit_msgs/JointConstraint"; }; + const char * getMD5(){ return "c02a15146bec0ce13564807805b008f0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/JointLimits.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,121 @@ +#ifndef _ROS_moveit_msgs_JointLimits_h +#define _ROS_moveit_msgs_JointLimits_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class JointLimits : public ros::Msg + { + public: + const char* joint_name; + bool has_position_limits; + float min_position; + float max_position; + bool has_velocity_limits; + float max_velocity; + bool has_acceleration_limits; + float max_acceleration; + + JointLimits(): + joint_name(""), + has_position_limits(0), + min_position(0), + max_position(0), + has_velocity_limits(0), + max_velocity(0), + has_acceleration_limits(0), + max_acceleration(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_joint_name = strlen(this->joint_name); + memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_name, length_joint_name); + offset += length_joint_name; + union { + bool real; + uint8_t base; + } u_has_position_limits; + u_has_position_limits.real = this->has_position_limits; + *(outbuffer + offset + 0) = (u_has_position_limits.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->has_position_limits); + offset += serializeAvrFloat64(outbuffer + offset, this->min_position); + offset += serializeAvrFloat64(outbuffer + offset, this->max_position); + union { + bool real; + uint8_t base; + } u_has_velocity_limits; + u_has_velocity_limits.real = this->has_velocity_limits; + *(outbuffer + offset + 0) = (u_has_velocity_limits.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->has_velocity_limits); + offset += serializeAvrFloat64(outbuffer + offset, this->max_velocity); + union { + bool real; + uint8_t base; + } u_has_acceleration_limits; + u_has_acceleration_limits.real = this->has_acceleration_limits; + *(outbuffer + offset + 0) = (u_has_acceleration_limits.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->has_acceleration_limits); + offset += serializeAvrFloat64(outbuffer + offset, this->max_acceleration); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_joint_name; + memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_joint_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_joint_name-1]=0; + this->joint_name = (char *)(inbuffer + offset-1); + offset += length_joint_name; + union { + bool real; + uint8_t base; + } u_has_position_limits; + u_has_position_limits.base = 0; + u_has_position_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->has_position_limits = u_has_position_limits.real; + offset += sizeof(this->has_position_limits); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_position)); + union { + bool real; + uint8_t base; + } u_has_velocity_limits; + u_has_velocity_limits.base = 0; + u_has_velocity_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->has_velocity_limits = u_has_velocity_limits.real; + offset += sizeof(this->has_velocity_limits); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_velocity)); + union { + bool real; + uint8_t base; + } u_has_acceleration_limits; + u_has_acceleration_limits.base = 0; + u_has_acceleration_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->has_acceleration_limits = u_has_acceleration_limits.real; + offset += sizeof(this->has_acceleration_limits); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_acceleration)); + return offset; + } + + const char * getType(){ return "moveit_msgs/JointLimits"; }; + const char * getMD5(){ return "8ca618c7329ea46142cbc864a2efe856"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/KinematicSolverInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,123 @@ +#ifndef _ROS_moveit_msgs_KinematicSolverInfo_h +#define _ROS_moveit_msgs_KinematicSolverInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/JointLimits.h" + +namespace moveit_msgs +{ + + class KinematicSolverInfo : public ros::Msg + { + public: + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t limits_length; + moveit_msgs::JointLimits st_limits; + moveit_msgs::JointLimits * limits; + uint8_t link_names_length; + char* st_link_names; + char* * link_names; + + KinematicSolverInfo(): + joint_names_length(0), joint_names(NULL), + limits_length(0), limits(NULL), + link_names_length(0), link_names(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = limits_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < limits_length; i++){ + offset += this->limits[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = link_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < link_names_length; i++){ + uint32_t length_link_namesi = strlen(this->link_names[i]); + memcpy(outbuffer + offset, &length_link_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_names[i], length_link_namesi); + offset += length_link_namesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t limits_lengthT = *(inbuffer + offset++); + if(limits_lengthT > limits_length) + this->limits = (moveit_msgs::JointLimits*)realloc(this->limits, limits_lengthT * sizeof(moveit_msgs::JointLimits)); + offset += 3; + limits_length = limits_lengthT; + for( uint8_t i = 0; i < limits_length; i++){ + offset += this->st_limits.deserialize(inbuffer + offset); + memcpy( &(this->limits[i]), &(this->st_limits), sizeof(moveit_msgs::JointLimits)); + } + uint8_t link_names_lengthT = *(inbuffer + offset++); + if(link_names_lengthT > link_names_length) + this->link_names = (char**)realloc(this->link_names, link_names_lengthT * sizeof(char*)); + offset += 3; + link_names_length = link_names_lengthT; + for( uint8_t i = 0; i < link_names_length; i++){ + uint32_t length_st_link_names; + memcpy(&length_st_link_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_link_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_link_names-1]=0; + this->st_link_names = (char *)(inbuffer + offset-1); + offset += length_st_link_names; + memcpy( &(this->link_names[i]), &(this->st_link_names), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/KinematicSolverInfo"; }; + const char * getMD5(){ return "cc048557c0f9795c392dd80f8bb00489"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/LinkPadding.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_moveit_msgs_LinkPadding_h +#define _ROS_moveit_msgs_LinkPadding_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class LinkPadding : public ros::Msg + { + public: + const char* link_name; + float padding; + + LinkPadding(): + link_name(""), + padding(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += serializeAvrFloat64(outbuffer + offset, this->padding); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->padding)); + return offset; + } + + const char * getType(){ return "moveit_msgs/LinkPadding"; }; + const char * getMD5(){ return "b3ea75670df55c696fedee97774d5947"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/LinkScale.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_moveit_msgs_LinkScale_h +#define _ROS_moveit_msgs_LinkScale_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class LinkScale : public ros::Msg + { + public: + const char* link_name; + float scale; + + LinkScale(): + link_name(""), + scale(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += serializeAvrFloat64(outbuffer + offset, this->scale); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->scale)); + return offset; + } + + const char * getType(){ return "moveit_msgs/LinkScale"; }; + const char * getMD5(){ return "19faf226446bfb2f645a4da6f2a56166"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/LoadMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_LoadMap_h +#define _ROS_SERVICE_LoadMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + +static const char LOADMAP[] = "moveit_msgs/LoadMap"; + + class LoadMapRequest : public ros::Msg + { + public: + const char* filename; + + LoadMapRequest(): + filename("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_filename = strlen(this->filename); + memcpy(outbuffer + offset, &length_filename, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->filename, length_filename); + offset += length_filename; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_filename; + memcpy(&length_filename, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_filename; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_filename-1]=0; + this->filename = (char *)(inbuffer + offset-1); + offset += length_filename; + return offset; + } + + const char * getType(){ return LOADMAP; }; + const char * getMD5(){ return "030824f52a0628ead956fb9d67e66ae9"; }; + + }; + + class LoadMapResponse : public ros::Msg + { + public: + bool success; + + LoadMapResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return LOADMAP; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class LoadMap { + public: + typedef LoadMapRequest Request; + typedef LoadMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MotionPlanDetailedResponse.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,137 @@ +#ifndef _ROS_moveit_msgs_MotionPlanDetailedResponse_h +#define _ROS_moveit_msgs_MotionPlanDetailedResponse_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/MoveItErrorCodes.h" + +namespace moveit_msgs +{ + + class MotionPlanDetailedResponse : public ros::Msg + { + public: + moveit_msgs::RobotState trajectory_start; + const char* group_name; + uint8_t trajectory_length; + moveit_msgs::RobotTrajectory st_trajectory; + moveit_msgs::RobotTrajectory * trajectory; + uint8_t description_length; + char* st_description; + char* * description; + uint8_t processing_time_length; + float st_processing_time; + float * processing_time; + moveit_msgs::MoveItErrorCodes error_code; + + MotionPlanDetailedResponse(): + trajectory_start(), + group_name(""), + trajectory_length(0), trajectory(NULL), + description_length(0), description(NULL), + processing_time_length(0), processing_time(NULL), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->trajectory_start.serialize(outbuffer + offset); + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + *(outbuffer + offset++) = trajectory_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_length; i++){ + offset += this->trajectory[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = description_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < description_length; i++){ + uint32_t length_descriptioni = strlen(this->description[i]); + memcpy(outbuffer + offset, &length_descriptioni, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->description[i], length_descriptioni); + offset += length_descriptioni; + } + *(outbuffer + offset++) = processing_time_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < processing_time_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->processing_time[i]); + } + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->trajectory_start.deserialize(inbuffer + offset); + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + uint8_t trajectory_lengthT = *(inbuffer + offset++); + if(trajectory_lengthT > trajectory_length) + this->trajectory = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory, trajectory_lengthT * sizeof(moveit_msgs::RobotTrajectory)); + offset += 3; + trajectory_length = trajectory_lengthT; + for( uint8_t i = 0; i < trajectory_length; i++){ + offset += this->st_trajectory.deserialize(inbuffer + offset); + memcpy( &(this->trajectory[i]), &(this->st_trajectory), sizeof(moveit_msgs::RobotTrajectory)); + } + uint8_t description_lengthT = *(inbuffer + offset++); + if(description_lengthT > description_length) + this->description = (char**)realloc(this->description, description_lengthT * sizeof(char*)); + offset += 3; + description_length = description_lengthT; + for( uint8_t i = 0; i < description_length; i++){ + uint32_t length_st_description; + memcpy(&length_st_description, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_description; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_description-1]=0; + this->st_description = (char *)(inbuffer + offset-1); + offset += length_st_description; + memcpy( &(this->description[i]), &(this->st_description), sizeof(char*)); + } + uint8_t processing_time_lengthT = *(inbuffer + offset++); + if(processing_time_lengthT > processing_time_length) + this->processing_time = (float*)realloc(this->processing_time, processing_time_lengthT * sizeof(float)); + offset += 3; + processing_time_length = processing_time_lengthT; + for( uint8_t i = 0; i < processing_time_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_processing_time)); + memcpy( &(this->processing_time[i]), &(this->st_processing_time), sizeof(float)); + } + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/MotionPlanDetailedResponse"; }; + const char * getMD5(){ return "7b84c374bb2e37bdc0eba664f7636a8f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MotionPlanRequest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,137 @@ +#ifndef _ROS_moveit_msgs_MotionPlanRequest_h +#define _ROS_moveit_msgs_MotionPlanRequest_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/WorkspaceParameters.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/Constraints.h" +#include "moveit_msgs/TrajectoryConstraints.h" + +namespace moveit_msgs +{ + + class MotionPlanRequest : public ros::Msg + { + public: + moveit_msgs::WorkspaceParameters workspace_parameters; + moveit_msgs::RobotState start_state; + uint8_t goal_constraints_length; + moveit_msgs::Constraints st_goal_constraints; + moveit_msgs::Constraints * goal_constraints; + moveit_msgs::Constraints path_constraints; + moveit_msgs::TrajectoryConstraints trajectory_constraints; + const char* planner_id; + const char* group_name; + int32_t num_planning_attempts; + float allowed_planning_time; + + MotionPlanRequest(): + workspace_parameters(), + start_state(), + goal_constraints_length(0), goal_constraints(NULL), + path_constraints(), + trajectory_constraints(), + planner_id(""), + group_name(""), + num_planning_attempts(0), + allowed_planning_time(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->workspace_parameters.serialize(outbuffer + offset); + offset += this->start_state.serialize(outbuffer + offset); + *(outbuffer + offset++) = goal_constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < goal_constraints_length; i++){ + offset += this->goal_constraints[i].serialize(outbuffer + offset); + } + offset += this->path_constraints.serialize(outbuffer + offset); + offset += this->trajectory_constraints.serialize(outbuffer + offset); + uint32_t length_planner_id = strlen(this->planner_id); + memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->planner_id, length_planner_id); + offset += length_planner_id; + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + union { + int32_t real; + uint32_t base; + } u_num_planning_attempts; + u_num_planning_attempts.real = this->num_planning_attempts; + *(outbuffer + offset + 0) = (u_num_planning_attempts.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_num_planning_attempts.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_num_planning_attempts.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_num_planning_attempts.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->num_planning_attempts); + offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->workspace_parameters.deserialize(inbuffer + offset); + offset += this->start_state.deserialize(inbuffer + offset); + uint8_t goal_constraints_lengthT = *(inbuffer + offset++); + if(goal_constraints_lengthT > goal_constraints_length) + this->goal_constraints = (moveit_msgs::Constraints*)realloc(this->goal_constraints, goal_constraints_lengthT * sizeof(moveit_msgs::Constraints)); + offset += 3; + goal_constraints_length = goal_constraints_lengthT; + for( uint8_t i = 0; i < goal_constraints_length; i++){ + offset += this->st_goal_constraints.deserialize(inbuffer + offset); + memcpy( &(this->goal_constraints[i]), &(this->st_goal_constraints), sizeof(moveit_msgs::Constraints)); + } + offset += this->path_constraints.deserialize(inbuffer + offset); + offset += this->trajectory_constraints.deserialize(inbuffer + offset); + uint32_t length_planner_id; + memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_planner_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_planner_id-1]=0; + this->planner_id = (char *)(inbuffer + offset-1); + offset += length_planner_id; + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + union { + int32_t real; + uint32_t base; + } u_num_planning_attempts; + u_num_planning_attempts.base = 0; + u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->num_planning_attempts = u_num_planning_attempts.real; + offset += sizeof(this->num_planning_attempts); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time)); + return offset; + } + + const char * getType(){ return "moveit_msgs/MotionPlanRequest"; }; + const char * getMD5(){ return "7cd790e04c3a55f6742ec387a72a02d6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MotionPlanResponse.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,73 @@ +#ifndef _ROS_moveit_msgs_MotionPlanResponse_h +#define _ROS_moveit_msgs_MotionPlanResponse_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/MoveItErrorCodes.h" + +namespace moveit_msgs +{ + + class MotionPlanResponse : public ros::Msg + { + public: + moveit_msgs::RobotState trajectory_start; + const char* group_name; + moveit_msgs::RobotTrajectory trajectory; + float planning_time; + moveit_msgs::MoveItErrorCodes error_code; + + MotionPlanResponse(): + trajectory_start(), + group_name(""), + trajectory(), + planning_time(0), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->trajectory_start.serialize(outbuffer + offset); + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + offset += this->trajectory.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->planning_time); + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->trajectory_start.deserialize(inbuffer + offset); + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + offset += this->trajectory.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->planning_time)); + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/MotionPlanResponse"; }; + const char * getMD5(){ return "e493d20ab41424c48f671e152c70fc74"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_MoveGroupAction_h +#define _ROS_moveit_msgs_MoveGroupAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveGroupActionGoal.h" +#include "moveit_msgs/MoveGroupActionResult.h" +#include "moveit_msgs/MoveGroupActionFeedback.h" + +namespace moveit_msgs +{ + + class MoveGroupAction : public ros::Msg + { + public: + moveit_msgs::MoveGroupActionGoal action_goal; + moveit_msgs::MoveGroupActionResult action_result; + moveit_msgs::MoveGroupActionFeedback action_feedback; + + MoveGroupAction(): + 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 "moveit_msgs/MoveGroupAction"; }; + const char * getMD5(){ return "d50bd38d1cf3e7b2d84a542b5441c796"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_MoveGroupActionFeedback_h +#define _ROS_moveit_msgs_MoveGroupActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/MoveGroupFeedback.h" + +namespace moveit_msgs +{ + + class MoveGroupActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::MoveGroupFeedback feedback; + + MoveGroupActionFeedback(): + 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 "moveit_msgs/MoveGroupActionFeedback"; }; + const char * getMD5(){ return "12232ef97486c7962f264c105aae2958"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_MoveGroupActionGoal_h +#define _ROS_moveit_msgs_MoveGroupActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "moveit_msgs/MoveGroupGoal.h" + +namespace moveit_msgs +{ + + class MoveGroupActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + moveit_msgs::MoveGroupGoal goal; + + MoveGroupActionGoal(): + 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 "moveit_msgs/MoveGroupActionGoal"; }; + const char * getMD5(){ return "5a63f1e432efa5831f25bdbf4067e372"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_MoveGroupActionResult_h +#define _ROS_moveit_msgs_MoveGroupActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/MoveGroupResult.h" + +namespace moveit_msgs +{ + + class MoveGroupActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::MoveGroupResult result; + + MoveGroupActionResult(): + 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 "moveit_msgs/MoveGroupActionResult"; }; + const char * getMD5(){ return "6ee8682a508d60603228accdc4a2b30b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_moveit_msgs_MoveGroupFeedback_h +#define _ROS_moveit_msgs_MoveGroupFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class MoveGroupFeedback : public ros::Msg + { + public: + const char* state; + + MoveGroupFeedback(): + state("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_state = strlen(this->state); + memcpy(outbuffer + offset, &length_state, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->state, length_state); + offset += length_state; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_state; + memcpy(&length_state, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_state; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_state-1]=0; + this->state = (char *)(inbuffer + offset-1); + offset += length_state; + return offset; + } + + const char * getType(){ return "moveit_msgs/MoveGroupFeedback"; }; + const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_moveit_msgs_MoveGroupGoal_h +#define _ROS_moveit_msgs_MoveGroupGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MotionPlanRequest.h" +#include "moveit_msgs/PlanningOptions.h" + +namespace moveit_msgs +{ + + class MoveGroupGoal : public ros::Msg + { + public: + moveit_msgs::MotionPlanRequest request; + moveit_msgs::PlanningOptions planning_options; + + MoveGroupGoal(): + request(), + planning_options() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->request.serialize(outbuffer + offset); + offset += this->planning_options.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->request.deserialize(inbuffer + offset); + offset += this->planning_options.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/MoveGroupGoal"; }; + const char * getMD5(){ return "6f87a65b68d345a6821303c17412a990"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveGroupResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_moveit_msgs_MoveGroupResult_h +#define _ROS_moveit_msgs_MoveGroupResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/RobotTrajectory.h" + +namespace moveit_msgs +{ + + class MoveGroupResult : public ros::Msg + { + public: + moveit_msgs::MoveItErrorCodes error_code; + moveit_msgs::RobotState trajectory_start; + moveit_msgs::RobotTrajectory planned_trajectory; + moveit_msgs::RobotTrajectory executed_trajectory; + float planning_time; + + MoveGroupResult(): + error_code(), + trajectory_start(), + planned_trajectory(), + executed_trajectory(), + planning_time(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->error_code.serialize(outbuffer + offset); + offset += this->trajectory_start.serialize(outbuffer + offset); + offset += this->planned_trajectory.serialize(outbuffer + offset); + offset += this->executed_trajectory.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->planning_time); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->error_code.deserialize(inbuffer + offset); + offset += this->trajectory_start.deserialize(inbuffer + offset); + offset += this->planned_trajectory.deserialize(inbuffer + offset); + offset += this->executed_trajectory.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->planning_time)); + return offset; + } + + const char * getType(){ return "moveit_msgs/MoveGroupResult"; }; + const char * getMD5(){ return "34098589d402fee7ae9c3fd413e5a6c6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/MoveItErrorCodes.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,85 @@ +#ifndef _ROS_moveit_msgs_MoveItErrorCodes_h +#define _ROS_moveit_msgs_MoveItErrorCodes_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class MoveItErrorCodes : public ros::Msg + { + public: + int32_t val; + enum { SUCCESS = 1 }; + enum { FAILURE = 99999 }; + enum { PLANNING_FAILED = -1 }; + enum { INVALID_MOTION_PLAN = -2 }; + enum { MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE = -3 }; + enum { CONTROL_FAILED = -4 }; + enum { UNABLE_TO_AQUIRE_SENSOR_DATA = -5 }; + enum { TIMED_OUT = -6 }; + enum { PREEMPTED = -7 }; + enum { START_STATE_IN_COLLISION = -10 }; + enum { START_STATE_VIOLATES_PATH_CONSTRAINTS = -11 }; + enum { GOAL_IN_COLLISION = -12 }; + enum { GOAL_VIOLATES_PATH_CONSTRAINTS = -13 }; + enum { GOAL_CONSTRAINTS_VIOLATED = -14 }; + enum { INVALID_GROUP_NAME = -15 }; + enum { INVALID_GOAL_CONSTRAINTS = -16 }; + enum { INVALID_ROBOT_STATE = -17 }; + enum { INVALID_LINK_NAME = -18 }; + enum { INVALID_OBJECT_NAME = -19 }; + enum { FRAME_TRANSFORM_FAILURE = -21 }; + enum { COLLISION_CHECKING_UNAVAILABLE = -22 }; + enum { ROBOT_STATE_STALE = -23 }; + enum { SENSOR_INFO_STALE = -24 }; + enum { NO_IK_SOLUTION = -31 }; + + MoveItErrorCodes(): + val(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_val; + u_val.real = this->val; + *(outbuffer + offset + 0) = (u_val.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_val.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_val.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_val.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->val); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_val; + u_val.base = 0; + u_val.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_val.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_val.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_val.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->val = u_val.real; + offset += sizeof(this->val); + return offset; + } + + const char * getType(){ return "moveit_msgs/MoveItErrorCodes"; }; + const char * getMD5(){ return "aa336b18d80531f66439810112c0a43e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/ObjectColor.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_moveit_msgs_ObjectColor_h +#define _ROS_moveit_msgs_ObjectColor_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/ColorRGBA.h" + +namespace moveit_msgs +{ + + class ObjectColor : public ros::Msg + { + public: + const char* id; + std_msgs::ColorRGBA color; + + ObjectColor(): + id(""), + color() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->color.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->color.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/ObjectColor"; }; + const char * getMD5(){ return "ec3bd6f103430e64b2ae706a67d8488e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/OrientationConstraint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_moveit_msgs_OrientationConstraint_h +#define _ROS_moveit_msgs_OrientationConstraint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" + +namespace moveit_msgs +{ + + class OrientationConstraint : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Quaternion orientation; + const char* link_name; + float absolute_x_axis_tolerance; + float absolute_y_axis_tolerance; + float absolute_z_axis_tolerance; + float weight; + + OrientationConstraint(): + header(), + orientation(), + link_name(""), + absolute_x_axis_tolerance(0), + absolute_y_axis_tolerance(0), + absolute_z_axis_tolerance(0), + weight(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->orientation.serialize(outbuffer + offset); + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += serializeAvrFloat64(outbuffer + offset, this->absolute_x_axis_tolerance); + offset += serializeAvrFloat64(outbuffer + offset, this->absolute_y_axis_tolerance); + offset += serializeAvrFloat64(outbuffer + offset, this->absolute_z_axis_tolerance); + offset += serializeAvrFloat64(outbuffer + offset, this->weight); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_x_axis_tolerance)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_y_axis_tolerance)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_z_axis_tolerance)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); + return offset; + } + + const char * getType(){ return "moveit_msgs/OrientationConstraint"; }; + const char * getMD5(){ return "ab5cefb9bc4c0089620f5eb4caf4e59a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/OrientedBoundingBox.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_moveit_msgs_OrientedBoundingBox_h +#define _ROS_moveit_msgs_OrientedBoundingBox_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Point32.h" + +namespace moveit_msgs +{ + + class OrientedBoundingBox : public ros::Msg + { + public: + geometry_msgs::Pose pose; + geometry_msgs::Point32 extents; + + OrientedBoundingBox(): + pose(), + extents() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->pose.serialize(outbuffer + offset); + offset += this->extents.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->extents.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/OrientedBoundingBox"; }; + const char * getMD5(){ return "da3bd98e7cb14efa4141367a9d886ee7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PickupAction_h +#define _ROS_moveit_msgs_PickupAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PickupActionGoal.h" +#include "moveit_msgs/PickupActionResult.h" +#include "moveit_msgs/PickupActionFeedback.h" + +namespace moveit_msgs +{ + + class PickupAction : public ros::Msg + { + public: + moveit_msgs::PickupActionGoal action_goal; + moveit_msgs::PickupActionResult action_result; + moveit_msgs::PickupActionFeedback action_feedback; + + PickupAction(): + 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 "moveit_msgs/PickupAction"; }; + const char * getMD5(){ return "f5aa574f57e5d9cf7d466d5913039489"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PickupActionFeedback_h +#define _ROS_moveit_msgs_PickupActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/PickupFeedback.h" + +namespace moveit_msgs +{ + + class PickupActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::PickupFeedback feedback; + + PickupActionFeedback(): + 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 "moveit_msgs/PickupActionFeedback"; }; + const char * getMD5(){ return "12232ef97486c7962f264c105aae2958"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PickupActionGoal_h +#define _ROS_moveit_msgs_PickupActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "moveit_msgs/PickupGoal.h" + +namespace moveit_msgs +{ + + class PickupActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + moveit_msgs::PickupGoal goal; + + PickupActionGoal(): + 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 "moveit_msgs/PickupActionGoal"; }; + const char * getMD5(){ return "9e12196da542c9a26bbc43e9655a1906"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PickupActionResult_h +#define _ROS_moveit_msgs_PickupActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/PickupResult.h" + +namespace moveit_msgs +{ + + class PickupActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::PickupResult result; + + PickupActionResult(): + 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 "moveit_msgs/PickupActionResult"; }; + const char * getMD5(){ return "9a2192bdd4f78c9d7c479e4a43f2768f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_moveit_msgs_PickupFeedback_h +#define _ROS_moveit_msgs_PickupFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class PickupFeedback : public ros::Msg + { + public: + const char* state; + + PickupFeedback(): + state("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_state = strlen(this->state); + memcpy(outbuffer + offset, &length_state, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->state, length_state); + offset += length_state; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_state; + memcpy(&length_state, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_state; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_state-1]=0; + this->state = (char *)(inbuffer + offset-1); + offset += length_state; + return offset; + } + + const char * getType(){ return "moveit_msgs/PickupFeedback"; }; + const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,251 @@ +#ifndef _ROS_moveit_msgs_PickupGoal_h +#define _ROS_moveit_msgs_PickupGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/Grasp.h" +#include "moveit_msgs/Constraints.h" +#include "moveit_msgs/PlanningOptions.h" + +namespace moveit_msgs +{ + + class PickupGoal : public ros::Msg + { + public: + const char* target_name; + const char* group_name; + const char* end_effector; + uint8_t possible_grasps_length; + moveit_msgs::Grasp st_possible_grasps; + moveit_msgs::Grasp * possible_grasps; + const char* support_surface_name; + bool allow_gripper_support_collision; + uint8_t attached_object_touch_links_length; + char* st_attached_object_touch_links; + char* * attached_object_touch_links; + bool minimize_object_distance; + moveit_msgs::Constraints path_constraints; + const char* planner_id; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + float allowed_planning_time; + moveit_msgs::PlanningOptions planning_options; + + PickupGoal(): + target_name(""), + group_name(""), + end_effector(""), + possible_grasps_length(0), possible_grasps(NULL), + support_surface_name(""), + allow_gripper_support_collision(0), + attached_object_touch_links_length(0), attached_object_touch_links(NULL), + minimize_object_distance(0), + path_constraints(), + planner_id(""), + allowed_touch_objects_length(0), allowed_touch_objects(NULL), + allowed_planning_time(0), + planning_options() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_target_name = strlen(this->target_name); + memcpy(outbuffer + offset, &length_target_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->target_name, length_target_name); + offset += length_target_name; + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + uint32_t length_end_effector = strlen(this->end_effector); + memcpy(outbuffer + offset, &length_end_effector, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->end_effector, length_end_effector); + offset += length_end_effector; + *(outbuffer + offset++) = possible_grasps_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < possible_grasps_length; i++){ + offset += this->possible_grasps[i].serialize(outbuffer + offset); + } + uint32_t length_support_surface_name = strlen(this->support_surface_name); + memcpy(outbuffer + offset, &length_support_surface_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name); + offset += length_support_surface_name; + union { + bool real; + uint8_t base; + } u_allow_gripper_support_collision; + u_allow_gripper_support_collision.real = this->allow_gripper_support_collision; + *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->allow_gripper_support_collision); + *(outbuffer + offset++) = attached_object_touch_links_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < attached_object_touch_links_length; i++){ + uint32_t length_attached_object_touch_linksi = strlen(this->attached_object_touch_links[i]); + memcpy(outbuffer + offset, &length_attached_object_touch_linksi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->attached_object_touch_links[i], length_attached_object_touch_linksi); + offset += length_attached_object_touch_linksi; + } + union { + bool real; + uint8_t base; + } u_minimize_object_distance; + u_minimize_object_distance.real = this->minimize_object_distance; + *(outbuffer + offset + 0) = (u_minimize_object_distance.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->minimize_object_distance); + offset += this->path_constraints.serialize(outbuffer + offset); + uint32_t length_planner_id = strlen(this->planner_id); + memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->planner_id, length_planner_id); + offset += length_planner_id; + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time); + offset += this->planning_options.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_target_name; + memcpy(&length_target_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_target_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_target_name-1]=0; + this->target_name = (char *)(inbuffer + offset-1); + offset += length_target_name; + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + uint32_t length_end_effector; + memcpy(&length_end_effector, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_end_effector; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_end_effector-1]=0; + this->end_effector = (char *)(inbuffer + offset-1); + offset += length_end_effector; + uint8_t possible_grasps_lengthT = *(inbuffer + offset++); + if(possible_grasps_lengthT > possible_grasps_length) + this->possible_grasps = (moveit_msgs::Grasp*)realloc(this->possible_grasps, possible_grasps_lengthT * sizeof(moveit_msgs::Grasp)); + offset += 3; + possible_grasps_length = possible_grasps_lengthT; + for( uint8_t i = 0; i < possible_grasps_length; i++){ + offset += this->st_possible_grasps.deserialize(inbuffer + offset); + memcpy( &(this->possible_grasps[i]), &(this->st_possible_grasps), sizeof(moveit_msgs::Grasp)); + } + uint32_t length_support_surface_name; + memcpy(&length_support_surface_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_support_surface_name-1]=0; + this->support_surface_name = (char *)(inbuffer + offset-1); + offset += length_support_surface_name; + union { + bool real; + uint8_t base; + } u_allow_gripper_support_collision; + u_allow_gripper_support_collision.base = 0; + u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->allow_gripper_support_collision = u_allow_gripper_support_collision.real; + offset += sizeof(this->allow_gripper_support_collision); + uint8_t attached_object_touch_links_lengthT = *(inbuffer + offset++); + if(attached_object_touch_links_lengthT > attached_object_touch_links_length) + this->attached_object_touch_links = (char**)realloc(this->attached_object_touch_links, attached_object_touch_links_lengthT * sizeof(char*)); + offset += 3; + attached_object_touch_links_length = attached_object_touch_links_lengthT; + for( uint8_t i = 0; i < attached_object_touch_links_length; i++){ + uint32_t length_st_attached_object_touch_links; + memcpy(&length_st_attached_object_touch_links, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_attached_object_touch_links; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_attached_object_touch_links-1]=0; + this->st_attached_object_touch_links = (char *)(inbuffer + offset-1); + offset += length_st_attached_object_touch_links; + memcpy( &(this->attached_object_touch_links[i]), &(this->st_attached_object_touch_links), sizeof(char*)); + } + union { + bool real; + uint8_t base; + } u_minimize_object_distance; + u_minimize_object_distance.base = 0; + u_minimize_object_distance.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->minimize_object_distance = u_minimize_object_distance.real; + offset += sizeof(this->minimize_object_distance); + offset += this->path_constraints.deserialize(inbuffer + offset); + uint32_t length_planner_id; + memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_planner_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_planner_id-1]=0; + this->planner_id = (char *)(inbuffer + offset-1); + offset += length_planner_id; + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time)); + offset += this->planning_options.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/PickupGoal"; }; + const char * getMD5(){ return "458c6ab3761d73e99b070063f7b74c2a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PickupResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,106 @@ +#ifndef _ROS_moveit_msgs_PickupResult_h +#define _ROS_moveit_msgs_PickupResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/Grasp.h" + +namespace moveit_msgs +{ + + class PickupResult : public ros::Msg + { + public: + moveit_msgs::MoveItErrorCodes error_code; + moveit_msgs::RobotState trajectory_start; + uint8_t trajectory_stages_length; + moveit_msgs::RobotTrajectory st_trajectory_stages; + moveit_msgs::RobotTrajectory * trajectory_stages; + uint8_t trajectory_descriptions_length; + char* st_trajectory_descriptions; + char* * trajectory_descriptions; + moveit_msgs::Grasp grasp; + + PickupResult(): + error_code(), + trajectory_start(), + trajectory_stages_length(0), trajectory_stages(NULL), + trajectory_descriptions_length(0), trajectory_descriptions(NULL), + grasp() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->error_code.serialize(outbuffer + offset); + offset += this->trajectory_start.serialize(outbuffer + offset); + *(outbuffer + offset++) = trajectory_stages_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_stages_length; i++){ + offset += this->trajectory_stages[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = trajectory_descriptions_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_descriptions_length; i++){ + uint32_t length_trajectory_descriptionsi = strlen(this->trajectory_descriptions[i]); + memcpy(outbuffer + offset, &length_trajectory_descriptionsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->trajectory_descriptions[i], length_trajectory_descriptionsi); + offset += length_trajectory_descriptionsi; + } + offset += this->grasp.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->error_code.deserialize(inbuffer + offset); + offset += this->trajectory_start.deserialize(inbuffer + offset); + uint8_t trajectory_stages_lengthT = *(inbuffer + offset++); + if(trajectory_stages_lengthT > trajectory_stages_length) + this->trajectory_stages = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory_stages, trajectory_stages_lengthT * sizeof(moveit_msgs::RobotTrajectory)); + offset += 3; + trajectory_stages_length = trajectory_stages_lengthT; + for( uint8_t i = 0; i < trajectory_stages_length; i++){ + offset += this->st_trajectory_stages.deserialize(inbuffer + offset); + memcpy( &(this->trajectory_stages[i]), &(this->st_trajectory_stages), sizeof(moveit_msgs::RobotTrajectory)); + } + uint8_t trajectory_descriptions_lengthT = *(inbuffer + offset++); + if(trajectory_descriptions_lengthT > trajectory_descriptions_length) + this->trajectory_descriptions = (char**)realloc(this->trajectory_descriptions, trajectory_descriptions_lengthT * sizeof(char*)); + offset += 3; + trajectory_descriptions_length = trajectory_descriptions_lengthT; + for( uint8_t i = 0; i < trajectory_descriptions_length; i++){ + uint32_t length_st_trajectory_descriptions; + memcpy(&length_st_trajectory_descriptions, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_trajectory_descriptions; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_trajectory_descriptions-1]=0; + this->st_trajectory_descriptions = (char *)(inbuffer + offset-1); + offset += length_st_trajectory_descriptions; + memcpy( &(this->trajectory_descriptions[i]), &(this->st_trajectory_descriptions), sizeof(char*)); + } + offset += this->grasp.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/PickupResult"; }; + const char * getMD5(){ return "23c6d8bf0580f4bc8f7a8e1f59b4b6b7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PlaceAction_h +#define _ROS_moveit_msgs_PlaceAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PlaceActionGoal.h" +#include "moveit_msgs/PlaceActionResult.h" +#include "moveit_msgs/PlaceActionFeedback.h" + +namespace moveit_msgs +{ + + class PlaceAction : public ros::Msg + { + public: + moveit_msgs::PlaceActionGoal action_goal; + moveit_msgs::PlaceActionResult action_result; + moveit_msgs::PlaceActionFeedback action_feedback; + + PlaceAction(): + 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 "moveit_msgs/PlaceAction"; }; + const char * getMD5(){ return "28cb4b6b7c2a211726c2c78386a9da69"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PlaceActionFeedback_h +#define _ROS_moveit_msgs_PlaceActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/PlaceFeedback.h" + +namespace moveit_msgs +{ + + class PlaceActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::PlaceFeedback feedback; + + PlaceActionFeedback(): + 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 "moveit_msgs/PlaceActionFeedback"; }; + const char * getMD5(){ return "12232ef97486c7962f264c105aae2958"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PlaceActionGoal_h +#define _ROS_moveit_msgs_PlaceActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "moveit_msgs/PlaceGoal.h" + +namespace moveit_msgs +{ + + class PlaceActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + moveit_msgs::PlaceGoal goal; + + PlaceActionGoal(): + 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 "moveit_msgs/PlaceActionGoal"; }; + const char * getMD5(){ return "facadaee390f685ed5e693ac12f5aa3d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_moveit_msgs_PlaceActionResult_h +#define _ROS_moveit_msgs_PlaceActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "moveit_msgs/PlaceResult.h" + +namespace moveit_msgs +{ + + class PlaceActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + moveit_msgs::PlaceResult result; + + PlaceActionResult(): + 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 "moveit_msgs/PlaceActionResult"; }; + const char * getMD5(){ return "d7a2ac2299b16bfd9120d347472b7cdc"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_moveit_msgs_PlaceFeedback_h +#define _ROS_moveit_msgs_PlaceFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class PlaceFeedback : public ros::Msg + { + public: + const char* state; + + PlaceFeedback(): + state("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_state = strlen(this->state); + memcpy(outbuffer + offset, &length_state, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->state, length_state); + offset += length_state; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_state; + memcpy(&length_state, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_state; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_state-1]=0; + this->state = (char *)(inbuffer + offset-1); + offset += length_state; + return offset; + } + + const char * getType(){ return "moveit_msgs/PlaceFeedback"; }; + const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,203 @@ +#ifndef _ROS_moveit_msgs_PlaceGoal_h +#define _ROS_moveit_msgs_PlaceGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PlaceLocation.h" +#include "moveit_msgs/Constraints.h" +#include "moveit_msgs/PlanningOptions.h" + +namespace moveit_msgs +{ + + class PlaceGoal : public ros::Msg + { + public: + const char* group_name; + const char* attached_object_name; + uint8_t place_locations_length; + moveit_msgs::PlaceLocation st_place_locations; + moveit_msgs::PlaceLocation * place_locations; + bool place_eef; + const char* support_surface_name; + bool allow_gripper_support_collision; + moveit_msgs::Constraints path_constraints; + const char* planner_id; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + float allowed_planning_time; + moveit_msgs::PlanningOptions planning_options; + + PlaceGoal(): + group_name(""), + attached_object_name(""), + place_locations_length(0), place_locations(NULL), + place_eef(0), + support_surface_name(""), + allow_gripper_support_collision(0), + path_constraints(), + planner_id(""), + allowed_touch_objects_length(0), allowed_touch_objects(NULL), + allowed_planning_time(0), + planning_options() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + uint32_t length_attached_object_name = strlen(this->attached_object_name); + memcpy(outbuffer + offset, &length_attached_object_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->attached_object_name, length_attached_object_name); + offset += length_attached_object_name; + *(outbuffer + offset++) = place_locations_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < place_locations_length; i++){ + offset += this->place_locations[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_place_eef; + u_place_eef.real = this->place_eef; + *(outbuffer + offset + 0) = (u_place_eef.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->place_eef); + uint32_t length_support_surface_name = strlen(this->support_surface_name); + memcpy(outbuffer + offset, &length_support_surface_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name); + offset += length_support_surface_name; + union { + bool real; + uint8_t base; + } u_allow_gripper_support_collision; + u_allow_gripper_support_collision.real = this->allow_gripper_support_collision; + *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->allow_gripper_support_collision); + offset += this->path_constraints.serialize(outbuffer + offset); + uint32_t length_planner_id = strlen(this->planner_id); + memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->planner_id, length_planner_id); + offset += length_planner_id; + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time); + offset += this->planning_options.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + uint32_t length_attached_object_name; + memcpy(&length_attached_object_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_attached_object_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_attached_object_name-1]=0; + this->attached_object_name = (char *)(inbuffer + offset-1); + offset += length_attached_object_name; + uint8_t place_locations_lengthT = *(inbuffer + offset++); + if(place_locations_lengthT > place_locations_length) + this->place_locations = (moveit_msgs::PlaceLocation*)realloc(this->place_locations, place_locations_lengthT * sizeof(moveit_msgs::PlaceLocation)); + offset += 3; + place_locations_length = place_locations_lengthT; + for( uint8_t i = 0; i < place_locations_length; i++){ + offset += this->st_place_locations.deserialize(inbuffer + offset); + memcpy( &(this->place_locations[i]), &(this->st_place_locations), sizeof(moveit_msgs::PlaceLocation)); + } + union { + bool real; + uint8_t base; + } u_place_eef; + u_place_eef.base = 0; + u_place_eef.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->place_eef = u_place_eef.real; + offset += sizeof(this->place_eef); + uint32_t length_support_surface_name; + memcpy(&length_support_surface_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_support_surface_name-1]=0; + this->support_surface_name = (char *)(inbuffer + offset-1); + offset += length_support_surface_name; + union { + bool real; + uint8_t base; + } u_allow_gripper_support_collision; + u_allow_gripper_support_collision.base = 0; + u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->allow_gripper_support_collision = u_allow_gripper_support_collision.real; + offset += sizeof(this->allow_gripper_support_collision); + offset += this->path_constraints.deserialize(inbuffer + offset); + uint32_t length_planner_id; + memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_planner_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_planner_id-1]=0; + this->planner_id = (char *)(inbuffer + offset-1); + offset += length_planner_id; + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time)); + offset += this->planning_options.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlaceGoal"; }; + const char * getMD5(){ return "e3f3e956e536ccd313fd8f23023f0a94"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceLocation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,105 @@ +#ifndef _ROS_moveit_msgs_PlaceLocation_h +#define _ROS_moveit_msgs_PlaceLocation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "geometry_msgs/PoseStamped.h" +#include "moveit_msgs/GripperTranslation.h" + +namespace moveit_msgs +{ + + class PlaceLocation : public ros::Msg + { + public: + const char* id; + trajectory_msgs::JointTrajectory post_place_posture; + geometry_msgs::PoseStamped place_pose; + moveit_msgs::GripperTranslation pre_place_approach; + moveit_msgs::GripperTranslation post_place_retreat; + uint8_t allowed_touch_objects_length; + char* st_allowed_touch_objects; + char* * allowed_touch_objects; + + PlaceLocation(): + id(""), + post_place_posture(), + place_pose(), + pre_place_approach(), + post_place_retreat(), + allowed_touch_objects_length(0), allowed_touch_objects(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += this->post_place_posture.serialize(outbuffer + offset); + offset += this->place_pose.serialize(outbuffer + offset); + offset += this->pre_place_approach.serialize(outbuffer + offset); + offset += this->post_place_retreat.serialize(outbuffer + offset); + *(outbuffer + offset++) = allowed_touch_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); + memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); + offset += length_allowed_touch_objectsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += this->post_place_posture.deserialize(inbuffer + offset); + offset += this->place_pose.deserialize(inbuffer + offset); + offset += this->pre_place_approach.deserialize(inbuffer + offset); + offset += this->post_place_retreat.deserialize(inbuffer + offset); + uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); + if(allowed_touch_objects_lengthT > allowed_touch_objects_length) + this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); + offset += 3; + allowed_touch_objects_length = allowed_touch_objects_lengthT; + for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ + uint32_t length_st_allowed_touch_objects; + memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_allowed_touch_objects-1]=0; + this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); + offset += length_st_allowed_touch_objects; + memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/PlaceLocation"; }; + const char * getMD5(){ return "f3dbcaca40fb29ede2af78b3e1831128"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlaceResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,106 @@ +#ifndef _ROS_moveit_msgs_PlaceResult_h +#define _ROS_moveit_msgs_PlaceResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/RobotTrajectory.h" +#include "moveit_msgs/PlaceLocation.h" + +namespace moveit_msgs +{ + + class PlaceResult : public ros::Msg + { + public: + moveit_msgs::MoveItErrorCodes error_code; + moveit_msgs::RobotState trajectory_start; + uint8_t trajectory_stages_length; + moveit_msgs::RobotTrajectory st_trajectory_stages; + moveit_msgs::RobotTrajectory * trajectory_stages; + uint8_t trajectory_descriptions_length; + char* st_trajectory_descriptions; + char* * trajectory_descriptions; + moveit_msgs::PlaceLocation place_location; + + PlaceResult(): + error_code(), + trajectory_start(), + trajectory_stages_length(0), trajectory_stages(NULL), + trajectory_descriptions_length(0), trajectory_descriptions(NULL), + place_location() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->error_code.serialize(outbuffer + offset); + offset += this->trajectory_start.serialize(outbuffer + offset); + *(outbuffer + offset++) = trajectory_stages_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_stages_length; i++){ + offset += this->trajectory_stages[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = trajectory_descriptions_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < trajectory_descriptions_length; i++){ + uint32_t length_trajectory_descriptionsi = strlen(this->trajectory_descriptions[i]); + memcpy(outbuffer + offset, &length_trajectory_descriptionsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->trajectory_descriptions[i], length_trajectory_descriptionsi); + offset += length_trajectory_descriptionsi; + } + offset += this->place_location.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->error_code.deserialize(inbuffer + offset); + offset += this->trajectory_start.deserialize(inbuffer + offset); + uint8_t trajectory_stages_lengthT = *(inbuffer + offset++); + if(trajectory_stages_lengthT > trajectory_stages_length) + this->trajectory_stages = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory_stages, trajectory_stages_lengthT * sizeof(moveit_msgs::RobotTrajectory)); + offset += 3; + trajectory_stages_length = trajectory_stages_lengthT; + for( uint8_t i = 0; i < trajectory_stages_length; i++){ + offset += this->st_trajectory_stages.deserialize(inbuffer + offset); + memcpy( &(this->trajectory_stages[i]), &(this->st_trajectory_stages), sizeof(moveit_msgs::RobotTrajectory)); + } + uint8_t trajectory_descriptions_lengthT = *(inbuffer + offset++); + if(trajectory_descriptions_lengthT > trajectory_descriptions_length) + this->trajectory_descriptions = (char**)realloc(this->trajectory_descriptions, trajectory_descriptions_lengthT * sizeof(char*)); + offset += 3; + trajectory_descriptions_length = trajectory_descriptions_lengthT; + for( uint8_t i = 0; i < trajectory_descriptions_length; i++){ + uint32_t length_st_trajectory_descriptions; + memcpy(&length_st_trajectory_descriptions, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_trajectory_descriptions; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_trajectory_descriptions-1]=0; + this->st_trajectory_descriptions = (char *)(inbuffer + offset-1); + offset += length_st_trajectory_descriptions; + memcpy( &(this->trajectory_descriptions[i]), &(this->st_trajectory_descriptions), sizeof(char*)); + } + offset += this->place_location.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlaceResult"; }; + const char * getMD5(){ return "da2eea14de05cf0aa280f150a84ded50"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlannerInterfaceDescription.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,86 @@ +#ifndef _ROS_moveit_msgs_PlannerInterfaceDescription_h +#define _ROS_moveit_msgs_PlannerInterfaceDescription_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class PlannerInterfaceDescription : public ros::Msg + { + public: + const char* name; + uint8_t planner_ids_length; + char* st_planner_ids; + char* * planner_ids; + + PlannerInterfaceDescription(): + name(""), + planner_ids_length(0), planner_ids(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset++) = planner_ids_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < planner_ids_length; i++){ + uint32_t length_planner_idsi = strlen(this->planner_ids[i]); + memcpy(outbuffer + offset, &length_planner_idsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->planner_ids[i], length_planner_idsi); + offset += length_planner_idsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint8_t planner_ids_lengthT = *(inbuffer + offset++); + if(planner_ids_lengthT > planner_ids_length) + this->planner_ids = (char**)realloc(this->planner_ids, planner_ids_lengthT * sizeof(char*)); + offset += 3; + planner_ids_length = planner_ids_lengthT; + for( uint8_t i = 0; i < planner_ids_length; i++){ + uint32_t length_st_planner_ids; + memcpy(&length_st_planner_ids, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_planner_ids; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_planner_ids-1]=0; + this->st_planner_ids = (char *)(inbuffer + offset-1); + offset += length_st_planner_ids; + memcpy( &(this->planner_ids[i]), &(this->st_planner_ids), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/PlannerInterfaceDescription"; }; + const char * getMD5(){ return "ea5f6e6129aa1b110ccda9900d2bf25e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlanningOptions.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,148 @@ +#ifndef _ROS_moveit_msgs_PlanningOptions_h +#define _ROS_moveit_msgs_PlanningOptions_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PlanningScene.h" + +namespace moveit_msgs +{ + + class PlanningOptions : public ros::Msg + { + public: + moveit_msgs::PlanningScene planning_scene_diff; + bool plan_only; + bool look_around; + int32_t look_around_attempts; + float max_safe_execution_cost; + bool replan; + int32_t replan_attempts; + float replan_delay; + + PlanningOptions(): + planning_scene_diff(), + plan_only(0), + look_around(0), + look_around_attempts(0), + max_safe_execution_cost(0), + replan(0), + replan_attempts(0), + replan_delay(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->planning_scene_diff.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_plan_only; + u_plan_only.real = this->plan_only; + *(outbuffer + offset + 0) = (u_plan_only.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->plan_only); + union { + bool real; + uint8_t base; + } u_look_around; + u_look_around.real = this->look_around; + *(outbuffer + offset + 0) = (u_look_around.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->look_around); + union { + int32_t real; + uint32_t base; + } u_look_around_attempts; + u_look_around_attempts.real = this->look_around_attempts; + *(outbuffer + offset + 0) = (u_look_around_attempts.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_look_around_attempts.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_look_around_attempts.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_look_around_attempts.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->look_around_attempts); + offset += serializeAvrFloat64(outbuffer + offset, this->max_safe_execution_cost); + union { + bool real; + uint8_t base; + } u_replan; + u_replan.real = this->replan; + *(outbuffer + offset + 0) = (u_replan.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->replan); + union { + int32_t real; + uint32_t base; + } u_replan_attempts; + u_replan_attempts.real = this->replan_attempts; + *(outbuffer + offset + 0) = (u_replan_attempts.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_replan_attempts.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_replan_attempts.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_replan_attempts.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->replan_attempts); + offset += serializeAvrFloat64(outbuffer + offset, this->replan_delay); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->planning_scene_diff.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_plan_only; + u_plan_only.base = 0; + u_plan_only.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->plan_only = u_plan_only.real; + offset += sizeof(this->plan_only); + union { + bool real; + uint8_t base; + } u_look_around; + u_look_around.base = 0; + u_look_around.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->look_around = u_look_around.real; + offset += sizeof(this->look_around); + union { + int32_t real; + uint32_t base; + } u_look_around_attempts; + u_look_around_attempts.base = 0; + u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->look_around_attempts = u_look_around_attempts.real; + offset += sizeof(this->look_around_attempts); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_safe_execution_cost)); + union { + bool real; + uint8_t base; + } u_replan; + u_replan.base = 0; + u_replan.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->replan = u_replan.real; + offset += sizeof(this->replan); + union { + int32_t real; + uint32_t base; + } u_replan_attempts; + u_replan_attempts.base = 0; + u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->replan_attempts = u_replan_attempts.real; + offset += sizeof(this->replan_attempts); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->replan_delay)); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlanningOptions"; }; + const char * getMD5(){ return "3934e50ede2ecea03e532aade900ab50"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlanningScene.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,186 @@ +#ifndef _ROS_moveit_msgs_PlanningScene_h +#define _ROS_moveit_msgs_PlanningScene_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotState.h" +#include "geometry_msgs/TransformStamped.h" +#include "moveit_msgs/AllowedCollisionMatrix.h" +#include "moveit_msgs/LinkPadding.h" +#include "moveit_msgs/LinkScale.h" +#include "moveit_msgs/ObjectColor.h" +#include "moveit_msgs/PlanningSceneWorld.h" + +namespace moveit_msgs +{ + + class PlanningScene : public ros::Msg + { + public: + const char* name; + moveit_msgs::RobotState robot_state; + const char* robot_model_name; + uint8_t fixed_frame_transforms_length; + geometry_msgs::TransformStamped st_fixed_frame_transforms; + geometry_msgs::TransformStamped * fixed_frame_transforms; + moveit_msgs::AllowedCollisionMatrix allowed_collision_matrix; + uint8_t link_padding_length; + moveit_msgs::LinkPadding st_link_padding; + moveit_msgs::LinkPadding * link_padding; + uint8_t link_scale_length; + moveit_msgs::LinkScale st_link_scale; + moveit_msgs::LinkScale * link_scale; + uint8_t object_colors_length; + moveit_msgs::ObjectColor st_object_colors; + moveit_msgs::ObjectColor * object_colors; + moveit_msgs::PlanningSceneWorld world; + bool is_diff; + + PlanningScene(): + name(""), + robot_state(), + robot_model_name(""), + fixed_frame_transforms_length(0), fixed_frame_transforms(NULL), + allowed_collision_matrix(), + link_padding_length(0), link_padding(NULL), + link_scale_length(0), link_scale(NULL), + object_colors_length(0), object_colors(NULL), + world(), + is_diff(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += this->robot_state.serialize(outbuffer + offset); + uint32_t length_robot_model_name = strlen(this->robot_model_name); + memcpy(outbuffer + offset, &length_robot_model_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->robot_model_name, length_robot_model_name); + offset += length_robot_model_name; + *(outbuffer + offset++) = fixed_frame_transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fixed_frame_transforms_length; i++){ + offset += this->fixed_frame_transforms[i].serialize(outbuffer + offset); + } + offset += this->allowed_collision_matrix.serialize(outbuffer + offset); + *(outbuffer + offset++) = link_padding_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < link_padding_length; i++){ + offset += this->link_padding[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = link_scale_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < link_scale_length; i++){ + offset += this->link_scale[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = object_colors_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < object_colors_length; i++){ + offset += this->object_colors[i].serialize(outbuffer + offset); + } + offset += this->world.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_is_diff; + u_is_diff.real = this->is_diff; + *(outbuffer + offset + 0) = (u_is_diff.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_diff); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += this->robot_state.deserialize(inbuffer + offset); + uint32_t length_robot_model_name; + memcpy(&length_robot_model_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_robot_model_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_robot_model_name-1]=0; + this->robot_model_name = (char *)(inbuffer + offset-1); + offset += length_robot_model_name; + uint8_t fixed_frame_transforms_lengthT = *(inbuffer + offset++); + if(fixed_frame_transforms_lengthT > fixed_frame_transforms_length) + this->fixed_frame_transforms = (geometry_msgs::TransformStamped*)realloc(this->fixed_frame_transforms, fixed_frame_transforms_lengthT * sizeof(geometry_msgs::TransformStamped)); + offset += 3; + fixed_frame_transforms_length = fixed_frame_transforms_lengthT; + for( uint8_t i = 0; i < fixed_frame_transforms_length; i++){ + offset += this->st_fixed_frame_transforms.deserialize(inbuffer + offset); + memcpy( &(this->fixed_frame_transforms[i]), &(this->st_fixed_frame_transforms), sizeof(geometry_msgs::TransformStamped)); + } + offset += this->allowed_collision_matrix.deserialize(inbuffer + offset); + uint8_t link_padding_lengthT = *(inbuffer + offset++); + if(link_padding_lengthT > link_padding_length) + this->link_padding = (moveit_msgs::LinkPadding*)realloc(this->link_padding, link_padding_lengthT * sizeof(moveit_msgs::LinkPadding)); + offset += 3; + link_padding_length = link_padding_lengthT; + for( uint8_t i = 0; i < link_padding_length; i++){ + offset += this->st_link_padding.deserialize(inbuffer + offset); + memcpy( &(this->link_padding[i]), &(this->st_link_padding), sizeof(moveit_msgs::LinkPadding)); + } + uint8_t link_scale_lengthT = *(inbuffer + offset++); + if(link_scale_lengthT > link_scale_length) + this->link_scale = (moveit_msgs::LinkScale*)realloc(this->link_scale, link_scale_lengthT * sizeof(moveit_msgs::LinkScale)); + offset += 3; + link_scale_length = link_scale_lengthT; + for( uint8_t i = 0; i < link_scale_length; i++){ + offset += this->st_link_scale.deserialize(inbuffer + offset); + memcpy( &(this->link_scale[i]), &(this->st_link_scale), sizeof(moveit_msgs::LinkScale)); + } + uint8_t object_colors_lengthT = *(inbuffer + offset++); + if(object_colors_lengthT > object_colors_length) + this->object_colors = (moveit_msgs::ObjectColor*)realloc(this->object_colors, object_colors_lengthT * sizeof(moveit_msgs::ObjectColor)); + offset += 3; + object_colors_length = object_colors_lengthT; + for( uint8_t i = 0; i < object_colors_length; i++){ + offset += this->st_object_colors.deserialize(inbuffer + offset); + memcpy( &(this->object_colors[i]), &(this->st_object_colors), sizeof(moveit_msgs::ObjectColor)); + } + offset += this->world.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_is_diff; + u_is_diff.base = 0; + u_is_diff.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_diff = u_is_diff.real; + offset += sizeof(this->is_diff); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlanningScene"; }; + const char * getMD5(){ return "89aac6d20db967ba716cba5a86b1b9d5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlanningSceneComponents.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,60 @@ +#ifndef _ROS_moveit_msgs_PlanningSceneComponents_h +#define _ROS_moveit_msgs_PlanningSceneComponents_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + + class PlanningSceneComponents : public ros::Msg + { + public: + uint32_t components; + enum { SCENE_SETTINGS = 1 }; + enum { ROBOT_STATE = 2 }; + enum { ROBOT_STATE_ATTACHED_OBJECTS = 4 }; + enum { WORLD_OBJECT_NAMES = 8 }; + enum { WORLD_OBJECT_GEOMETRY = 16 }; + enum { OCTOMAP = 32 }; + enum { TRANSFORMS = 64 }; + enum { ALLOWED_COLLISION_MATRIX = 128 }; + enum { LINK_PADDING_AND_SCALING = 256 }; + enum { OBJECT_COLORS = 512 }; + + PlanningSceneComponents(): + components(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->components >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->components >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->components >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->components >> (8 * 3)) & 0xFF; + offset += sizeof(this->components); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->components = ((uint32_t) (*(inbuffer + offset))); + this->components |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->components |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->components |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->components); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlanningSceneComponents"; }; + const char * getMD5(){ return "bc993e784476960b918b6e7ad5bb58ce"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PlanningSceneWorld.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_moveit_msgs_PlanningSceneWorld_h +#define _ROS_moveit_msgs_PlanningSceneWorld_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/CollisionObject.h" +#include "octomap_msgs/OctomapWithPose.h" + +namespace moveit_msgs +{ + + class PlanningSceneWorld : public ros::Msg + { + public: + uint8_t collision_objects_length; + moveit_msgs::CollisionObject st_collision_objects; + moveit_msgs::CollisionObject * collision_objects; + octomap_msgs::OctomapWithPose octomap; + + PlanningSceneWorld(): + collision_objects_length(0), collision_objects(NULL), + octomap() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = collision_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < collision_objects_length; i++){ + offset += this->collision_objects[i].serialize(outbuffer + offset); + } + offset += this->octomap.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t collision_objects_lengthT = *(inbuffer + offset++); + if(collision_objects_lengthT > collision_objects_length) + this->collision_objects = (moveit_msgs::CollisionObject*)realloc(this->collision_objects, collision_objects_lengthT * sizeof(moveit_msgs::CollisionObject)); + offset += 3; + collision_objects_length = collision_objects_lengthT; + for( uint8_t i = 0; i < collision_objects_length; i++){ + offset += this->st_collision_objects.deserialize(inbuffer + offset); + memcpy( &(this->collision_objects[i]), &(this->st_collision_objects), sizeof(moveit_msgs::CollisionObject)); + } + offset += this->octomap.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/PlanningSceneWorld"; }; + const char * getMD5(){ return "373d88390d1db385335639f687723ee6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PositionConstraint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,73 @@ +#ifndef _ROS_moveit_msgs_PositionConstraint_h +#define _ROS_moveit_msgs_PositionConstraint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Vector3.h" +#include "moveit_msgs/BoundingVolume.h" + +namespace moveit_msgs +{ + + class PositionConstraint : public ros::Msg + { + public: + std_msgs::Header header; + const char* link_name; + geometry_msgs::Vector3 target_point_offset; + moveit_msgs::BoundingVolume constraint_region; + float weight; + + PositionConstraint(): + header(), + link_name(""), + target_point_offset(), + constraint_region(), + weight(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_link_name = strlen(this->link_name); + memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->link_name, length_link_name); + offset += length_link_name; + offset += this->target_point_offset.serialize(outbuffer + offset); + offset += this->constraint_region.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->weight); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_link_name; + memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_link_name-1]=0; + this->link_name = (char *)(inbuffer + offset-1); + offset += length_link_name; + offset += this->target_point_offset.deserialize(inbuffer + offset); + offset += this->constraint_region.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); + return offset; + } + + const char * getType(){ return "moveit_msgs/PositionConstraint"; }; + const char * getMD5(){ return "c83edf208d87d3aa3169f47775a58e6a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/PositionIKRequest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,200 @@ +#ifndef _ROS_moveit_msgs_PositionIKRequest_h +#define _ROS_moveit_msgs_PositionIKRequest_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/Constraints.h" +#include "geometry_msgs/PoseStamped.h" +#include "ros/duration.h" + +namespace moveit_msgs +{ + + class PositionIKRequest : public ros::Msg + { + public: + const char* group_name; + moveit_msgs::RobotState robot_state; + moveit_msgs::Constraints constraints; + bool avoid_collisions; + const char* ik_link_name; + geometry_msgs::PoseStamped pose_stamped; + uint8_t ik_link_names_length; + char* st_ik_link_names; + char* * ik_link_names; + uint8_t pose_stamped_vector_length; + geometry_msgs::PoseStamped st_pose_stamped_vector; + geometry_msgs::PoseStamped * pose_stamped_vector; + ros::Duration timeout; + int32_t attempts; + + PositionIKRequest(): + group_name(""), + robot_state(), + constraints(), + avoid_collisions(0), + ik_link_name(""), + pose_stamped(), + ik_link_names_length(0), ik_link_names(NULL), + pose_stamped_vector_length(0), pose_stamped_vector(NULL), + timeout(), + attempts(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_group_name = strlen(this->group_name); + memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->group_name, length_group_name); + offset += length_group_name; + offset += this->robot_state.serialize(outbuffer + offset); + offset += this->constraints.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_avoid_collisions; + u_avoid_collisions.real = this->avoid_collisions; + *(outbuffer + offset + 0) = (u_avoid_collisions.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->avoid_collisions); + uint32_t length_ik_link_name = strlen(this->ik_link_name); + memcpy(outbuffer + offset, &length_ik_link_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->ik_link_name, length_ik_link_name); + offset += length_ik_link_name; + offset += this->pose_stamped.serialize(outbuffer + offset); + *(outbuffer + offset++) = ik_link_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ik_link_names_length; i++){ + uint32_t length_ik_link_namesi = strlen(this->ik_link_names[i]); + memcpy(outbuffer + offset, &length_ik_link_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->ik_link_names[i], length_ik_link_namesi); + offset += length_ik_link_namesi; + } + *(outbuffer + offset++) = pose_stamped_vector_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < pose_stamped_vector_length; i++){ + offset += this->pose_stamped_vector[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.sec); + *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.nsec); + union { + int32_t real; + uint32_t base; + } u_attempts; + u_attempts.real = this->attempts; + *(outbuffer + offset + 0) = (u_attempts.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_attempts.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_attempts.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_attempts.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->attempts); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_group_name; + memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_group_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_group_name-1]=0; + this->group_name = (char *)(inbuffer + offset-1); + offset += length_group_name; + offset += this->robot_state.deserialize(inbuffer + offset); + offset += this->constraints.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_avoid_collisions; + u_avoid_collisions.base = 0; + u_avoid_collisions.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->avoid_collisions = u_avoid_collisions.real; + offset += sizeof(this->avoid_collisions); + uint32_t length_ik_link_name; + memcpy(&length_ik_link_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_ik_link_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_ik_link_name-1]=0; + this->ik_link_name = (char *)(inbuffer + offset-1); + offset += length_ik_link_name; + offset += this->pose_stamped.deserialize(inbuffer + offset); + uint8_t ik_link_names_lengthT = *(inbuffer + offset++); + if(ik_link_names_lengthT > ik_link_names_length) + this->ik_link_names = (char**)realloc(this->ik_link_names, ik_link_names_lengthT * sizeof(char*)); + offset += 3; + ik_link_names_length = ik_link_names_lengthT; + for( uint8_t i = 0; i < ik_link_names_length; i++){ + uint32_t length_st_ik_link_names; + memcpy(&length_st_ik_link_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_ik_link_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_ik_link_names-1]=0; + this->st_ik_link_names = (char *)(inbuffer + offset-1); + offset += length_st_ik_link_names; + memcpy( &(this->ik_link_names[i]), &(this->st_ik_link_names), sizeof(char*)); + } + uint8_t pose_stamped_vector_lengthT = *(inbuffer + offset++); + if(pose_stamped_vector_lengthT > pose_stamped_vector_length) + this->pose_stamped_vector = (geometry_msgs::PoseStamped*)realloc(this->pose_stamped_vector, pose_stamped_vector_lengthT * sizeof(geometry_msgs::PoseStamped)); + offset += 3; + pose_stamped_vector_length = pose_stamped_vector_lengthT; + for( uint8_t i = 0; i < pose_stamped_vector_length; i++){ + offset += this->st_pose_stamped_vector.deserialize(inbuffer + offset); + memcpy( &(this->pose_stamped_vector[i]), &(this->st_pose_stamped_vector), sizeof(geometry_msgs::PoseStamped)); + } + this->timeout.sec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.sec); + this->timeout.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.nsec); + union { + int32_t real; + uint32_t base; + } u_attempts; + u_attempts.base = 0; + u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->attempts = u_attempts.real; + offset += sizeof(this->attempts); + return offset; + } + + const char * getType(){ return "moveit_msgs/PositionIKRequest"; }; + const char * getMD5(){ return "9936dc239c90af180ec94a51596c96f2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/QueryPlannerInterfaces.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_QueryPlannerInterfaces_h +#define _ROS_SERVICE_QueryPlannerInterfaces_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/PlannerInterfaceDescription.h" + +namespace moveit_msgs +{ + +static const char QUERYPLANNERINTERFACES[] = "moveit_msgs/QueryPlannerInterfaces"; + + class QueryPlannerInterfacesRequest : public ros::Msg + { + public: + + QueryPlannerInterfacesRequest() + { + } + + 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 QUERYPLANNERINTERFACES; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class QueryPlannerInterfacesResponse : public ros::Msg + { + public: + uint8_t planner_interfaces_length; + moveit_msgs::PlannerInterfaceDescription st_planner_interfaces; + moveit_msgs::PlannerInterfaceDescription * planner_interfaces; + + QueryPlannerInterfacesResponse(): + planner_interfaces_length(0), planner_interfaces(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = planner_interfaces_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < planner_interfaces_length; i++){ + offset += this->planner_interfaces[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t planner_interfaces_lengthT = *(inbuffer + offset++); + if(planner_interfaces_lengthT > planner_interfaces_length) + this->planner_interfaces = (moveit_msgs::PlannerInterfaceDescription*)realloc(this->planner_interfaces, planner_interfaces_lengthT * sizeof(moveit_msgs::PlannerInterfaceDescription)); + offset += 3; + planner_interfaces_length = planner_interfaces_lengthT; + for( uint8_t i = 0; i < planner_interfaces_length; i++){ + offset += this->st_planner_interfaces.deserialize(inbuffer + offset); + memcpy( &(this->planner_interfaces[i]), &(this->st_planner_interfaces), sizeof(moveit_msgs::PlannerInterfaceDescription)); + } + return offset; + } + + const char * getType(){ return QUERYPLANNERINTERFACES; }; + const char * getMD5(){ return "acd3317a4c5631f33127fb428209db05"; }; + + }; + + class QueryPlannerInterfaces { + public: + typedef QueryPlannerInterfacesRequest Request; + typedef QueryPlannerInterfacesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/RobotState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,86 @@ +#ifndef _ROS_moveit_msgs_RobotState_h +#define _ROS_moveit_msgs_RobotState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/JointState.h" +#include "sensor_msgs/MultiDOFJointState.h" +#include "moveit_msgs/AttachedCollisionObject.h" + +namespace moveit_msgs +{ + + class RobotState : public ros::Msg + { + public: + sensor_msgs::JointState joint_state; + sensor_msgs::MultiDOFJointState multi_dof_joint_state; + uint8_t attached_collision_objects_length; + moveit_msgs::AttachedCollisionObject st_attached_collision_objects; + moveit_msgs::AttachedCollisionObject * attached_collision_objects; + bool is_diff; + + RobotState(): + joint_state(), + multi_dof_joint_state(), + attached_collision_objects_length(0), attached_collision_objects(NULL), + is_diff(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->joint_state.serialize(outbuffer + offset); + offset += this->multi_dof_joint_state.serialize(outbuffer + offset); + *(outbuffer + offset++) = attached_collision_objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < attached_collision_objects_length; i++){ + offset += this->attached_collision_objects[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_is_diff; + u_is_diff.real = this->is_diff; + *(outbuffer + offset + 0) = (u_is_diff.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_diff); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->joint_state.deserialize(inbuffer + offset); + offset += this->multi_dof_joint_state.deserialize(inbuffer + offset); + uint8_t attached_collision_objects_lengthT = *(inbuffer + offset++); + if(attached_collision_objects_lengthT > attached_collision_objects_length) + this->attached_collision_objects = (moveit_msgs::AttachedCollisionObject*)realloc(this->attached_collision_objects, attached_collision_objects_lengthT * sizeof(moveit_msgs::AttachedCollisionObject)); + offset += 3; + attached_collision_objects_length = attached_collision_objects_lengthT; + for( uint8_t i = 0; i < attached_collision_objects_length; i++){ + offset += this->st_attached_collision_objects.deserialize(inbuffer + offset); + memcpy( &(this->attached_collision_objects[i]), &(this->st_attached_collision_objects), sizeof(moveit_msgs::AttachedCollisionObject)); + } + union { + bool real; + uint8_t base; + } u_is_diff; + u_is_diff.base = 0; + u_is_diff.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_diff = u_is_diff.real; + offset += sizeof(this->is_diff); + return offset; + } + + const char * getType(){ return "moveit_msgs/RobotState"; }; + const char * getMD5(){ return "217a2e8e5547f4162b13a37db9cb4da4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/RobotTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_moveit_msgs_RobotTrajectory_h +#define _ROS_moveit_msgs_RobotTrajectory_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "trajectory_msgs/JointTrajectory.h" +#include "trajectory_msgs/MultiDOFJointTrajectory.h" + +namespace moveit_msgs +{ + + class RobotTrajectory : public ros::Msg + { + public: + trajectory_msgs::JointTrajectory joint_trajectory; + trajectory_msgs::MultiDOFJointTrajectory multi_dof_joint_trajectory; + + RobotTrajectory(): + joint_trajectory(), + multi_dof_joint_trajectory() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->joint_trajectory.serialize(outbuffer + offset); + offset += this->multi_dof_joint_trajectory.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->joint_trajectory.deserialize(inbuffer + offset); + offset += this->multi_dof_joint_trajectory.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/RobotTrajectory"; }; + const char * getMD5(){ return "dfa9556423d709a3729bcef664bddf67"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/SaveMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_SaveMap_h +#define _ROS_SERVICE_SaveMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace moveit_msgs +{ + +static const char SAVEMAP[] = "moveit_msgs/SaveMap"; + + class SaveMapRequest : public ros::Msg + { + public: + const char* filename; + + SaveMapRequest(): + filename("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_filename = strlen(this->filename); + memcpy(outbuffer + offset, &length_filename, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->filename, length_filename); + offset += length_filename; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_filename; + memcpy(&length_filename, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_filename; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_filename-1]=0; + this->filename = (char *)(inbuffer + offset-1); + offset += length_filename; + return offset; + } + + const char * getType(){ return SAVEMAP; }; + const char * getMD5(){ return "030824f52a0628ead956fb9d67e66ae9"; }; + + }; + + class SaveMapResponse : public ros::Msg + { + public: + bool success; + + SaveMapResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return SAVEMAP; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class SaveMap { + public: + typedef SaveMapRequest Request; + typedef SaveMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/TrajectoryConstraints.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_moveit_msgs_TrajectoryConstraints_h +#define _ROS_moveit_msgs_TrajectoryConstraints_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/Constraints.h" + +namespace moveit_msgs +{ + + class TrajectoryConstraints : public ros::Msg + { + public: + uint8_t constraints_length; + moveit_msgs::Constraints st_constraints; + moveit_msgs::Constraints * constraints; + + TrajectoryConstraints(): + constraints_length(0), constraints(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = constraints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < constraints_length; i++){ + offset += this->constraints[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t constraints_lengthT = *(inbuffer + offset++); + if(constraints_lengthT > constraints_length) + this->constraints = (moveit_msgs::Constraints*)realloc(this->constraints, constraints_lengthT * sizeof(moveit_msgs::Constraints)); + offset += 3; + constraints_length = constraints_lengthT; + for( uint8_t i = 0; i < constraints_length; i++){ + offset += this->st_constraints.deserialize(inbuffer + offset); + memcpy( &(this->constraints[i]), &(this->st_constraints), sizeof(moveit_msgs::Constraints)); + } + return offset; + } + + const char * getType(){ return "moveit_msgs/TrajectoryConstraints"; }; + const char * getMD5(){ return "461e1a732dfebb01e7d6c75d51a51eac"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/VisibilityConstraint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,95 @@ +#ifndef _ROS_moveit_msgs_VisibilityConstraint_h +#define _ROS_moveit_msgs_VisibilityConstraint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" + +namespace moveit_msgs +{ + + class VisibilityConstraint : public ros::Msg + { + public: + float target_radius; + geometry_msgs::PoseStamped target_pose; + int32_t cone_sides; + geometry_msgs::PoseStamped sensor_pose; + float max_view_angle; + float max_range_angle; + uint8_t sensor_view_direction; + float weight; + enum { SENSOR_Z = 0 }; + enum { SENSOR_Y = 1 }; + enum { SENSOR_X = 2 }; + + VisibilityConstraint(): + target_radius(0), + target_pose(), + cone_sides(0), + sensor_pose(), + max_view_angle(0), + max_range_angle(0), + sensor_view_direction(0), + weight(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->target_radius); + offset += this->target_pose.serialize(outbuffer + offset); + union { + int32_t real; + uint32_t base; + } u_cone_sides; + u_cone_sides.real = this->cone_sides; + *(outbuffer + offset + 0) = (u_cone_sides.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cone_sides.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cone_sides.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cone_sides.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cone_sides); + offset += this->sensor_pose.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->max_view_angle); + offset += serializeAvrFloat64(outbuffer + offset, this->max_range_angle); + *(outbuffer + offset + 0) = (this->sensor_view_direction >> (8 * 0)) & 0xFF; + offset += sizeof(this->sensor_view_direction); + offset += serializeAvrFloat64(outbuffer + offset, this->weight); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->target_radius)); + offset += this->target_pose.deserialize(inbuffer + offset); + union { + int32_t real; + uint32_t base; + } u_cone_sides; + u_cone_sides.base = 0; + u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->cone_sides = u_cone_sides.real; + offset += sizeof(this->cone_sides); + offset += this->sensor_pose.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_view_angle)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_range_angle)); + this->sensor_view_direction = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->sensor_view_direction); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); + return offset; + } + + const char * getType(){ return "moveit_msgs/VisibilityConstraint"; }; + const char * getMD5(){ return "62cda903bfe31ff2e5fcdc3810d577ad"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/WorkspaceParameters.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,52 @@ +#ifndef _ROS_moveit_msgs_WorkspaceParameters_h +#define _ROS_moveit_msgs_WorkspaceParameters_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Vector3.h" + +namespace moveit_msgs +{ + + class WorkspaceParameters : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Vector3 min_corner; + geometry_msgs::Vector3 max_corner; + + WorkspaceParameters(): + header(), + min_corner(), + max_corner() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->min_corner.serialize(outbuffer + offset); + offset += this->max_corner.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->min_corner.deserialize(inbuffer + offset); + offset += this->max_corner.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "moveit_msgs/WorkspaceParameters"; }; + const char * getMD5(){ return "d639a834e7b1f927e9f1d6c30e920016"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_GetMap_h +#define _ROS_SERVICE_GetMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace nav_msgs +{ + +static const char GETMAP[] = "nav_msgs/GetMap"; + + class GetMapRequest : public ros::Msg + { + public: + + GetMapRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetMapResponse : public ros::Msg + { + public: + nav_msgs::OccupancyGrid map; + + GetMapResponse(): + map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMAP; }; + const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; + + }; + + class GetMap { + public: + typedef GetMapRequest Request; + typedef GetMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_nav_msgs_GetMapAction_h +#define _ROS_nav_msgs_GetMapAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/GetMapActionGoal.h" +#include "nav_msgs/GetMapActionResult.h" +#include "nav_msgs/GetMapActionFeedback.h" + +namespace nav_msgs +{ + + class GetMapAction : public ros::Msg + { + public: + nav_msgs::GetMapActionGoal action_goal; + nav_msgs::GetMapActionResult action_result; + nav_msgs::GetMapActionFeedback action_feedback; + + GetMapAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapAction"; }; + const char * getMD5(){ return "e611ad23fbf237c031b7536416dc7cd7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_nav_msgs_GetMapActionFeedback_h +#define _ROS_nav_msgs_GetMapActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "nav_msgs/GetMapFeedback.h" + +namespace nav_msgs +{ + + class GetMapActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + nav_msgs::GetMapFeedback feedback; + + GetMapActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_nav_msgs_GetMapActionGoal_h +#define _ROS_nav_msgs_GetMapActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "nav_msgs/GetMapGoal.h" + +namespace nav_msgs +{ + + class GetMapActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + nav_msgs::GetMapGoal goal; + + GetMapActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapActionGoal"; }; + const char * getMD5(){ return "4b30be6cd12b9e72826df56b481f40e0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_nav_msgs_GetMapActionResult_h +#define _ROS_nav_msgs_GetMapActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "nav_msgs/GetMapResult.h" + +namespace nav_msgs +{ + + class GetMapActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + nav_msgs::GetMapResult result; + + GetMapActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapActionResult"; }; + const char * getMD5(){ return "ac66e5b9a79bb4bbd33dab245236c892"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_nav_msgs_GetMapFeedback_h +#define _ROS_nav_msgs_GetMapFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace nav_msgs +{ + + class GetMapFeedback : public ros::Msg + { + public: + + GetMapFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_nav_msgs_GetMapGoal_h +#define _ROS_nav_msgs_GetMapGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace nav_msgs +{ + + class GetMapGoal : public ros::Msg + { + public: + + GetMapGoal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapGoal"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMapResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_nav_msgs_GetMapResult_h +#define _ROS_nav_msgs_GetMapResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace nav_msgs +{ + + class GetMapResult : public ros::Msg + { + public: + nav_msgs::OccupancyGrid map; + + GetMapResult(): + map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/GetMapResult"; }; + const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetPlan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,108 @@ +#ifndef _ROS_SERVICE_GetPlan_h +#define _ROS_SERVICE_GetPlan_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" +#include "nav_msgs/Path.h" + +namespace nav_msgs +{ + +static const char GETPLAN[] = "nav_msgs/GetPlan"; + + class GetPlanRequest : public ros::Msg + { + public: + geometry_msgs::PoseStamped start; + geometry_msgs::PoseStamped goal; + float tolerance; + + GetPlanRequest(): + start(), + goal(), + tolerance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->start.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_tolerance; + u_tolerance.real = this->tolerance; + *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->tolerance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->start.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_tolerance; + u_tolerance.base = 0; + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->tolerance = u_tolerance.real; + offset += sizeof(this->tolerance); + return offset; + } + + const char * getType(){ return GETPLAN; }; + const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; }; + + }; + + class GetPlanResponse : public ros::Msg + { + public: + nav_msgs::Path plan; + + GetPlanResponse(): + plan() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->plan.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->plan.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPLAN; }; + const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; }; + + }; + + class GetPlan { + public: + typedef GetPlanRequest Request; + typedef GetPlanResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GridCells.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,110 @@ +#ifndef _ROS_nav_msgs_GridCells_h +#define _ROS_nav_msgs_GridCells_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" + +namespace nav_msgs +{ + + class GridCells : public ros::Msg + { + public: + std_msgs::Header header; + float cell_width; + float cell_height; + uint8_t cells_length; + geometry_msgs::Point st_cells; + geometry_msgs::Point * cells; + + GridCells(): + header(), + cell_width(0), + cell_height(0), + cells_length(0), cells(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_cell_width; + u_cell_width.real = this->cell_width; + *(outbuffer + offset + 0) = (u_cell_width.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cell_width.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cell_width.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cell_width.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_width); + union { + float real; + uint32_t base; + } u_cell_height; + u_cell_height.real = this->cell_height; + *(outbuffer + offset + 0) = (u_cell_height.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cell_height.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cell_height.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cell_height.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_height); + *(outbuffer + offset++) = cells_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < cells_length; i++){ + offset += this->cells[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_cell_width; + u_cell_width.base = 0; + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->cell_width = u_cell_width.real; + offset += sizeof(this->cell_width); + union { + float real; + uint32_t base; + } u_cell_height; + u_cell_height.base = 0; + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->cell_height = u_cell_height.real; + offset += sizeof(this->cell_height); + uint8_t cells_lengthT = *(inbuffer + offset++); + if(cells_lengthT > cells_length) + this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + cells_length = cells_lengthT; + for( uint8_t i = 0; i < cells_length; i++){ + offset += this->st_cells.deserialize(inbuffer + offset); + memcpy( &(this->cells[i]), &(this->st_cells), sizeof(geometry_msgs::Point)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/GridCells"; }; + const char * getMD5(){ return "b9e4f5df6d28e272ebde00a3994830f5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/MapMetaData.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,113 @@ +#ifndef _ROS_nav_msgs_MapMetaData_h +#define _ROS_nav_msgs_MapMetaData_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "geometry_msgs/Pose.h" + +namespace nav_msgs +{ + + class MapMetaData : public ros::Msg + { + public: + ros::Time map_load_time; + float resolution; + uint32_t width; + uint32_t height; + geometry_msgs::Pose origin; + + MapMetaData(): + map_load_time(), + resolution(0), + width(0), + height(0), + origin() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->map_load_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->map_load_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->map_load_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->map_load_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->map_load_time.sec); + *(outbuffer + offset + 0) = (this->map_load_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->map_load_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->map_load_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->map_load_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->map_load_time.nsec); + union { + float real; + uint32_t base; + } u_resolution; + u_resolution.real = this->resolution; + *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_resolution.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->resolution); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + offset += this->origin.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->map_load_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->map_load_time.sec); + this->map_load_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->map_load_time.nsec); + union { + float real; + uint32_t base; + } u_resolution; + u_resolution.base = 0; + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->resolution = u_resolution.real; + offset += sizeof(this->resolution); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + offset += this->origin.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/MapMetaData"; }; + const char * getMD5(){ return "10cfc8a2818024d3248802c00c95f11b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/OccupancyGrid.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_nav_msgs_OccupancyGrid_h +#define _ROS_nav_msgs_OccupancyGrid_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "nav_msgs/MapMetaData.h" + +namespace nav_msgs +{ + + class OccupancyGrid : public ros::Msg + { + public: + std_msgs::Header header; + nav_msgs::MapMetaData info; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + OccupancyGrid(): + header(), + info(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->info.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->info.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/OccupancyGrid"; }; + const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/Odometry.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_nav_msgs_Odometry_h +#define _ROS_nav_msgs_Odometry_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseWithCovariance.h" +#include "geometry_msgs/TwistWithCovariance.h" + +namespace nav_msgs +{ + + class Odometry : public ros::Msg + { + public: + std_msgs::Header header; + const char* child_frame_id; + geometry_msgs::PoseWithCovariance pose; + geometry_msgs::TwistWithCovariance twist; + + Odometry(): + header(), + child_frame_id(""), + pose(), + twist() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_child_frame_id = strlen(this->child_frame_id); + memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id); + offset += length_child_frame_id; + offset += this->pose.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_child_frame_id; + memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_child_frame_id-1]=0; + this->child_frame_id = (char *)(inbuffer + offset-1); + offset += length_child_frame_id; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/Odometry"; }; + const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/Path.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_nav_msgs_Path_h +#define _ROS_nav_msgs_Path_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseStamped.h" + +namespace nav_msgs +{ + + class Path : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t poses_length; + geometry_msgs::PoseStamped st_poses; + geometry_msgs::PoseStamped * poses; + + Path(): + header(), + poses_length(0), poses(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->poses[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t poses_lengthT = *(inbuffer + offset++); + if(poses_lengthT > poses_length) + this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped)); + offset += 3; + poses_length = poses_lengthT; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->st_poses.deserialize(inbuffer + offset); + memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/Path"; }; + const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/navfn/MakeNavPlan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,122 @@ +#ifndef _ROS_SERVICE_MakeNavPlan_h +#define _ROS_SERVICE_MakeNavPlan_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" + +namespace navfn +{ + +static const char MAKENAVPLAN[] = "navfn/MakeNavPlan"; + + class MakeNavPlanRequest : public ros::Msg + { + public: + geometry_msgs::PoseStamped start; + geometry_msgs::PoseStamped goal; + + MakeNavPlanRequest(): + start(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->start.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->start.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return MAKENAVPLAN; }; + const char * getMD5(){ return "2fe3126bd5b2d56edd5005220333d4fd"; }; + + }; + + class MakeNavPlanResponse : public ros::Msg + { + public: + uint8_t plan_found; + const char* error_message; + uint8_t path_length; + geometry_msgs::PoseStamped st_path; + geometry_msgs::PoseStamped * path; + + MakeNavPlanResponse(): + plan_found(0), + error_message(""), + path_length(0), path(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->plan_found >> (8 * 0)) & 0xFF; + offset += sizeof(this->plan_found); + uint32_t length_error_message = strlen(this->error_message); + memcpy(outbuffer + offset, &length_error_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->error_message, length_error_message); + offset += length_error_message; + *(outbuffer + offset++) = path_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < path_length; i++){ + offset += this->path[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->plan_found = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->plan_found); + uint32_t length_error_message; + memcpy(&length_error_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_error_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_error_message-1]=0; + this->error_message = (char *)(inbuffer + offset-1); + offset += length_error_message; + uint8_t path_lengthT = *(inbuffer + offset++); + if(path_lengthT > path_length) + this->path = (geometry_msgs::PoseStamped*)realloc(this->path, path_lengthT * sizeof(geometry_msgs::PoseStamped)); + offset += 3; + path_length = path_lengthT; + for( uint8_t i = 0; i < path_length; i++){ + offset += this->st_path.deserialize(inbuffer + offset); + memcpy( &(this->path[i]), &(this->st_path), sizeof(geometry_msgs::PoseStamped)); + } + return offset; + } + + const char * getType(){ return MAKENAVPLAN; }; + const char * getMD5(){ return "8b8ed7edf1b237dc9ddda8c8ffed5d3a"; }; + + }; + + class MakeNavPlan { + public: + typedef MakeNavPlanRequest Request; + typedef MakeNavPlanResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/navfn/SetCostmap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,109 @@ +#ifndef _ROS_SERVICE_SetCostmap_h +#define _ROS_SERVICE_SetCostmap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace navfn +{ + +static const char SETCOSTMAP[] = "navfn/SetCostmap"; + + class SetCostmapRequest : public ros::Msg + { + public: + uint8_t costs_length; + uint8_t st_costs; + uint8_t * costs; + uint16_t height; + uint16_t width; + + SetCostmapRequest(): + costs_length(0), costs(NULL), + height(0), + width(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = costs_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < costs_length; i++){ + *(outbuffer + offset + 0) = (this->costs[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->costs[i]); + } + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + offset += sizeof(this->width); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t costs_lengthT = *(inbuffer + offset++); + if(costs_lengthT > costs_length) + this->costs = (uint8_t*)realloc(this->costs, costs_lengthT * sizeof(uint8_t)); + offset += 3; + costs_length = costs_lengthT; + for( uint8_t i = 0; i < costs_length; i++){ + this->st_costs = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_costs); + memcpy( &(this->costs[i]), &(this->st_costs), sizeof(uint8_t)); + } + this->height = ((uint16_t) (*(inbuffer + offset))); + this->height |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->height); + this->width = ((uint16_t) (*(inbuffer + offset))); + this->width |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->width); + return offset; + } + + const char * getType(){ return SETCOSTMAP; }; + const char * getMD5(){ return "370ec969cdb71f9cde7c7cbe0d752308"; }; + + }; + + class SetCostmapResponse : public ros::Msg + { + public: + + SetCostmapResponse() + { + } + + 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 SETCOSTMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetCostmap { + public: + typedef SetCostmapRequest Request; + typedef SetCostmapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nodelet/NodeletList.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_SERVICE_NodeletList_h +#define _ROS_SERVICE_NodeletList_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace nodelet +{ + +static const char NODELETLIST[] = "nodelet/NodeletList"; + + class NodeletListRequest : public ros::Msg + { + public: + + NodeletListRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return NODELETLIST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class NodeletListResponse : public ros::Msg + { + public: + uint8_t nodelets_length; + char* st_nodelets; + char* * nodelets; + + NodeletListResponse(): + nodelets_length(0), nodelets(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = nodelets_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < nodelets_length; i++){ + uint32_t length_nodeletsi = strlen(this->nodelets[i]); + memcpy(outbuffer + offset, &length_nodeletsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->nodelets[i], length_nodeletsi); + offset += length_nodeletsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t nodelets_lengthT = *(inbuffer + offset++); + if(nodelets_lengthT > nodelets_length) + this->nodelets = (char**)realloc(this->nodelets, nodelets_lengthT * sizeof(char*)); + offset += 3; + nodelets_length = nodelets_lengthT; + for( uint8_t i = 0; i < nodelets_length; i++){ + uint32_t length_st_nodelets; + memcpy(&length_st_nodelets, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_nodelets; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_nodelets-1]=0; + this->st_nodelets = (char *)(inbuffer + offset-1); + offset += length_st_nodelets; + memcpy( &(this->nodelets[i]), &(this->st_nodelets), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return NODELETLIST; }; + const char * getMD5(){ return "99c7b10e794f5600b8030e697e946ca7"; }; + + }; + + class NodeletList { + public: + typedef NodeletListRequest Request; + typedef NodeletListResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nodelet/NodeletLoad.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,232 @@ +#ifndef _ROS_SERVICE_NodeletLoad_h +#define _ROS_SERVICE_NodeletLoad_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace nodelet +{ + +static const char NODELETLOAD[] = "nodelet/NodeletLoad"; + + class NodeletLoadRequest : public ros::Msg + { + public: + const char* name; + const char* type; + uint8_t remap_source_args_length; + char* st_remap_source_args; + char* * remap_source_args; + uint8_t remap_target_args_length; + char* st_remap_target_args; + char* * remap_target_args; + uint8_t my_argv_length; + char* st_my_argv; + char* * my_argv; + const char* bond_id; + + NodeletLoadRequest(): + name(""), + type(""), + remap_source_args_length(0), remap_source_args(NULL), + remap_target_args_length(0), remap_target_args(NULL), + my_argv_length(0), my_argv(NULL), + bond_id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + *(outbuffer + offset++) = remap_source_args_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < remap_source_args_length; i++){ + uint32_t length_remap_source_argsi = strlen(this->remap_source_args[i]); + memcpy(outbuffer + offset, &length_remap_source_argsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->remap_source_args[i], length_remap_source_argsi); + offset += length_remap_source_argsi; + } + *(outbuffer + offset++) = remap_target_args_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < remap_target_args_length; i++){ + uint32_t length_remap_target_argsi = strlen(this->remap_target_args[i]); + memcpy(outbuffer + offset, &length_remap_target_argsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->remap_target_args[i], length_remap_target_argsi); + offset += length_remap_target_argsi; + } + *(outbuffer + offset++) = my_argv_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < my_argv_length; i++){ + uint32_t length_my_argvi = strlen(this->my_argv[i]); + memcpy(outbuffer + offset, &length_my_argvi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->my_argv[i], length_my_argvi); + offset += length_my_argvi; + } + uint32_t length_bond_id = strlen(this->bond_id); + memcpy(outbuffer + offset, &length_bond_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->bond_id, length_bond_id); + offset += length_bond_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + uint8_t remap_source_args_lengthT = *(inbuffer + offset++); + if(remap_source_args_lengthT > remap_source_args_length) + this->remap_source_args = (char**)realloc(this->remap_source_args, remap_source_args_lengthT * sizeof(char*)); + offset += 3; + remap_source_args_length = remap_source_args_lengthT; + for( uint8_t i = 0; i < remap_source_args_length; i++){ + uint32_t length_st_remap_source_args; + memcpy(&length_st_remap_source_args, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_remap_source_args; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_remap_source_args-1]=0; + this->st_remap_source_args = (char *)(inbuffer + offset-1); + offset += length_st_remap_source_args; + memcpy( &(this->remap_source_args[i]), &(this->st_remap_source_args), sizeof(char*)); + } + uint8_t remap_target_args_lengthT = *(inbuffer + offset++); + if(remap_target_args_lengthT > remap_target_args_length) + this->remap_target_args = (char**)realloc(this->remap_target_args, remap_target_args_lengthT * sizeof(char*)); + offset += 3; + remap_target_args_length = remap_target_args_lengthT; + for( uint8_t i = 0; i < remap_target_args_length; i++){ + uint32_t length_st_remap_target_args; + memcpy(&length_st_remap_target_args, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_remap_target_args; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_remap_target_args-1]=0; + this->st_remap_target_args = (char *)(inbuffer + offset-1); + offset += length_st_remap_target_args; + memcpy( &(this->remap_target_args[i]), &(this->st_remap_target_args), sizeof(char*)); + } + uint8_t my_argv_lengthT = *(inbuffer + offset++); + if(my_argv_lengthT > my_argv_length) + this->my_argv = (char**)realloc(this->my_argv, my_argv_lengthT * sizeof(char*)); + offset += 3; + my_argv_length = my_argv_lengthT; + for( uint8_t i = 0; i < my_argv_length; i++){ + uint32_t length_st_my_argv; + memcpy(&length_st_my_argv, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_my_argv; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_my_argv-1]=0; + this->st_my_argv = (char *)(inbuffer + offset-1); + offset += length_st_my_argv; + memcpy( &(this->my_argv[i]), &(this->st_my_argv), sizeof(char*)); + } + uint32_t length_bond_id; + memcpy(&length_bond_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_bond_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_bond_id-1]=0; + this->bond_id = (char *)(inbuffer + offset-1); + offset += length_bond_id; + return offset; + } + + const char * getType(){ return NODELETLOAD; }; + const char * getMD5(){ return "c6e28cc4d2e259249d96cfb50658fbec"; }; + + }; + + class NodeletLoadResponse : public ros::Msg + { + public: + bool success; + + NodeletLoadResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return NODELETLOAD; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class NodeletLoad { + public: + typedef NodeletLoadRequest Request; + typedef NodeletLoadResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nodelet/NodeletUnload.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_NodeletUnload_h +#define _ROS_SERVICE_NodeletUnload_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace nodelet +{ + +static const char NODELETUNLOAD[] = "nodelet/NodeletUnload"; + + class NodeletUnloadRequest : public ros::Msg + { + public: + const char* name; + + NodeletUnloadRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return NODELETUNLOAD; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class NodeletUnloadResponse : public ros::Msg + { + public: + bool success; + + NodeletUnloadResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return NODELETUNLOAD; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class NodeletUnload { + public: + typedef NodeletUnloadRequest Request; + typedef NodeletUnloadResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/GetObjectInformation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,81 @@ +#ifndef _ROS_SERVICE_GetObjectInformation_h +#define _ROS_SERVICE_GetObjectInformation_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "object_recognition_msgs/ObjectType.h" +#include "object_recognition_msgs/ObjectInformation.h" + +namespace object_recognition_msgs +{ + +static const char GETOBJECTINFORMATION[] = "object_recognition_msgs/GetObjectInformation"; + + class GetObjectInformationRequest : public ros::Msg + { + public: + object_recognition_msgs::ObjectType type; + + GetObjectInformationRequest(): + type() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->type.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->type.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETOBJECTINFORMATION; }; + const char * getMD5(){ return "0d72b69e80da0fe473b0bdcdd7a28d4d"; }; + + }; + + class GetObjectInformationResponse : public ros::Msg + { + public: + object_recognition_msgs::ObjectInformation information; + + GetObjectInformationResponse(): + information() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->information.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->information.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETOBJECTINFORMATION; }; + const char * getMD5(){ return "a62c5d1c41e250373b3e8e912a13a9cb"; }; + + }; + + class GetObjectInformation { + public: + typedef GetObjectInformationRequest Request; + typedef GetObjectInformationResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectInformation.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_object_recognition_msgs_ObjectInformation_h +#define _ROS_object_recognition_msgs_ObjectInformation_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "shape_msgs/Mesh.h" +#include "sensor_msgs/PointCloud2.h" + +namespace object_recognition_msgs +{ + + class ObjectInformation : public ros::Msg + { + public: + const char* name; + shape_msgs::Mesh ground_truth_mesh; + sensor_msgs::PointCloud2 ground_truth_point_cloud; + + ObjectInformation(): + name(""), + ground_truth_mesh(), + ground_truth_point_cloud() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += this->ground_truth_mesh.serialize(outbuffer + offset); + offset += this->ground_truth_point_cloud.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += this->ground_truth_mesh.deserialize(inbuffer + offset); + offset += this->ground_truth_point_cloud.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "object_recognition_msgs/ObjectInformation"; }; + const char * getMD5(){ return "921ec39f51c7b927902059cf3300ecde"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionAction_h +#define _ROS_object_recognition_msgs_ObjectRecognitionAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "object_recognition_msgs/ObjectRecognitionActionGoal.h" +#include "object_recognition_msgs/ObjectRecognitionActionResult.h" +#include "object_recognition_msgs/ObjectRecognitionActionFeedback.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionAction : public ros::Msg + { + public: + object_recognition_msgs::ObjectRecognitionActionGoal action_goal; + object_recognition_msgs::ObjectRecognitionActionResult action_result; + object_recognition_msgs::ObjectRecognitionActionFeedback action_feedback; + + ObjectRecognitionAction(): + 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 "object_recognition_msgs/ObjectRecognitionAction"; }; + const char * getMD5(){ return "7d8979a0cf97e5078553ee3efee047d2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionActionFeedback_h +#define _ROS_object_recognition_msgs_ObjectRecognitionActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "object_recognition_msgs/ObjectRecognitionFeedback.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + object_recognition_msgs::ObjectRecognitionFeedback feedback; + + ObjectRecognitionActionFeedback(): + 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 "object_recognition_msgs/ObjectRecognitionActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionActionGoal_h +#define _ROS_object_recognition_msgs_ObjectRecognitionActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "object_recognition_msgs/ObjectRecognitionGoal.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + object_recognition_msgs::ObjectRecognitionGoal goal; + + ObjectRecognitionActionGoal(): + 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 "object_recognition_msgs/ObjectRecognitionActionGoal"; }; + const char * getMD5(){ return "195eff91387a5f42dbd13be53431366b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionActionResult_h +#define _ROS_object_recognition_msgs_ObjectRecognitionActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "object_recognition_msgs/ObjectRecognitionResult.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + object_recognition_msgs::ObjectRecognitionResult result; + + ObjectRecognitionActionResult(): + 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 "object_recognition_msgs/ObjectRecognitionActionResult"; }; + const char * getMD5(){ return "1ef766aeca50bc1bb70773fc73d4471d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionFeedback_h +#define _ROS_object_recognition_msgs_ObjectRecognitionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionFeedback : public ros::Msg + { + public: + + ObjectRecognitionFeedback() + { + } + + 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 "object_recognition_msgs/ObjectRecognitionFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,94 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionGoal_h +#define _ROS_object_recognition_msgs_ObjectRecognitionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionGoal : public ros::Msg + { + public: + bool use_roi; + uint8_t filter_limits_length; + float st_filter_limits; + float * filter_limits; + + ObjectRecognitionGoal(): + use_roi(0), + filter_limits_length(0), filter_limits(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_use_roi; + u_use_roi.real = this->use_roi; + *(outbuffer + offset + 0) = (u_use_roi.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->use_roi); + *(outbuffer + offset++) = filter_limits_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < filter_limits_length; i++){ + union { + float real; + uint32_t base; + } u_filter_limitsi; + u_filter_limitsi.real = this->filter_limits[i]; + *(outbuffer + offset + 0) = (u_filter_limitsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_filter_limitsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_filter_limitsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_filter_limitsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->filter_limits[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_use_roi; + u_use_roi.base = 0; + u_use_roi.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->use_roi = u_use_roi.real; + offset += sizeof(this->use_roi); + uint8_t filter_limits_lengthT = *(inbuffer + offset++); + if(filter_limits_lengthT > filter_limits_length) + this->filter_limits = (float*)realloc(this->filter_limits, filter_limits_lengthT * sizeof(float)); + offset += 3; + filter_limits_length = filter_limits_lengthT; + for( uint8_t i = 0; i < filter_limits_length; i++){ + union { + float real; + uint32_t base; + } u_st_filter_limits; + u_st_filter_limits.base = 0; + u_st_filter_limits.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_filter_limits.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_filter_limits.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_filter_limits.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_filter_limits = u_st_filter_limits.real; + offset += sizeof(this->st_filter_limits); + memcpy( &(this->filter_limits[i]), &(this->st_filter_limits), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "object_recognition_msgs/ObjectRecognitionGoal"; }; + const char * getMD5(){ return "49bea2f03a1bba0ad05926e01e3525fa"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectRecognitionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,43 @@ +#ifndef _ROS_object_recognition_msgs_ObjectRecognitionResult_h +#define _ROS_object_recognition_msgs_ObjectRecognitionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "object_recognition_msgs/RecognizedObjectArray.h" + +namespace object_recognition_msgs +{ + + class ObjectRecognitionResult : public ros::Msg + { + public: + object_recognition_msgs::RecognizedObjectArray recognized_objects; + + ObjectRecognitionResult(): + recognized_objects() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->recognized_objects.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->recognized_objects.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "object_recognition_msgs/ObjectRecognitionResult"; }; + const char * getMD5(){ return "868e41288f9f8636e2b6c51f1af6aa9c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/ObjectType.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_object_recognition_msgs_ObjectType_h +#define _ROS_object_recognition_msgs_ObjectType_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace object_recognition_msgs +{ + + class ObjectType : public ros::Msg + { + public: + const char* key; + const char* db; + + ObjectType(): + key(""), + db("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_key = strlen(this->key); + memcpy(outbuffer + offset, &length_key, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->key, length_key); + offset += length_key; + uint32_t length_db = strlen(this->db); + memcpy(outbuffer + offset, &length_db, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->db, length_db); + offset += length_db; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_key; + memcpy(&length_key, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_key; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_key-1]=0; + this->key = (char *)(inbuffer + offset-1); + offset += length_key; + uint32_t length_db; + memcpy(&length_db, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_db; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_db-1]=0; + this->db = (char *)(inbuffer + offset-1); + offset += length_db; + return offset; + } + + const char * getType(){ return "object_recognition_msgs/ObjectType"; }; + const char * getMD5(){ return "ac757ec5be1998b0167e7efcda79e3cf"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/RecognizedObject.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,123 @@ +#ifndef _ROS_object_recognition_msgs_RecognizedObject_h +#define _ROS_object_recognition_msgs_RecognizedObject_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "object_recognition_msgs/ObjectType.h" +#include "sensor_msgs/PointCloud2.h" +#include "shape_msgs/Mesh.h" +#include "geometry_msgs/Point.h" +#include "geometry_msgs/PoseWithCovarianceStamped.h" + +namespace object_recognition_msgs +{ + + class RecognizedObject : public ros::Msg + { + public: + std_msgs::Header header; + object_recognition_msgs::ObjectType type; + float confidence; + uint8_t point_clouds_length; + sensor_msgs::PointCloud2 st_point_clouds; + sensor_msgs::PointCloud2 * point_clouds; + shape_msgs::Mesh bounding_mesh; + uint8_t bounding_contours_length; + geometry_msgs::Point st_bounding_contours; + geometry_msgs::Point * bounding_contours; + geometry_msgs::PoseWithCovarianceStamped pose; + + RecognizedObject(): + header(), + type(), + confidence(0), + point_clouds_length(0), point_clouds(NULL), + bounding_mesh(), + bounding_contours_length(0), bounding_contours(NULL), + pose() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->type.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_confidence; + u_confidence.real = this->confidence; + *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->confidence); + *(outbuffer + offset++) = point_clouds_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < point_clouds_length; i++){ + offset += this->point_clouds[i].serialize(outbuffer + offset); + } + offset += this->bounding_mesh.serialize(outbuffer + offset); + *(outbuffer + offset++) = bounding_contours_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < bounding_contours_length; i++){ + offset += this->bounding_contours[i].serialize(outbuffer + offset); + } + offset += this->pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->type.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_confidence; + u_confidence.base = 0; + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->confidence = u_confidence.real; + offset += sizeof(this->confidence); + uint8_t point_clouds_lengthT = *(inbuffer + offset++); + if(point_clouds_lengthT > point_clouds_length) + this->point_clouds = (sensor_msgs::PointCloud2*)realloc(this->point_clouds, point_clouds_lengthT * sizeof(sensor_msgs::PointCloud2)); + offset += 3; + point_clouds_length = point_clouds_lengthT; + for( uint8_t i = 0; i < point_clouds_length; i++){ + offset += this->st_point_clouds.deserialize(inbuffer + offset); + memcpy( &(this->point_clouds[i]), &(this->st_point_clouds), sizeof(sensor_msgs::PointCloud2)); + } + offset += this->bounding_mesh.deserialize(inbuffer + offset); + uint8_t bounding_contours_lengthT = *(inbuffer + offset++); + if(bounding_contours_lengthT > bounding_contours_length) + this->bounding_contours = (geometry_msgs::Point*)realloc(this->bounding_contours, bounding_contours_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + bounding_contours_length = bounding_contours_lengthT; + for( uint8_t i = 0; i < bounding_contours_length; i++){ + offset += this->st_bounding_contours.deserialize(inbuffer + offset); + memcpy( &(this->bounding_contours[i]), &(this->st_bounding_contours), sizeof(geometry_msgs::Point)); + } + offset += this->pose.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "object_recognition_msgs/RecognizedObject"; }; + const char * getMD5(){ return "f92c4cb29ba11f26c5f7219de97e900d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/RecognizedObjectArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_object_recognition_msgs_RecognizedObjectArray_h +#define _ROS_object_recognition_msgs_RecognizedObjectArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "object_recognition_msgs/RecognizedObject.h" + +namespace object_recognition_msgs +{ + + class RecognizedObjectArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t objects_length; + object_recognition_msgs::RecognizedObject st_objects; + object_recognition_msgs::RecognizedObject * objects; + uint8_t cooccurrence_length; + float st_cooccurrence; + float * cooccurrence; + + RecognizedObjectArray(): + header(), + objects_length(0), objects(NULL), + cooccurrence_length(0), cooccurrence(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = objects_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < objects_length; i++){ + offset += this->objects[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = cooccurrence_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < cooccurrence_length; i++){ + union { + float real; + uint32_t base; + } u_cooccurrencei; + u_cooccurrencei.real = this->cooccurrence[i]; + *(outbuffer + offset + 0) = (u_cooccurrencei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cooccurrencei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cooccurrencei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cooccurrencei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cooccurrence[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t objects_lengthT = *(inbuffer + offset++); + if(objects_lengthT > objects_length) + this->objects = (object_recognition_msgs::RecognizedObject*)realloc(this->objects, objects_lengthT * sizeof(object_recognition_msgs::RecognizedObject)); + offset += 3; + objects_length = objects_lengthT; + for( uint8_t i = 0; i < objects_length; i++){ + offset += this->st_objects.deserialize(inbuffer + offset); + memcpy( &(this->objects[i]), &(this->st_objects), sizeof(object_recognition_msgs::RecognizedObject)); + } + uint8_t cooccurrence_lengthT = *(inbuffer + offset++); + if(cooccurrence_lengthT > cooccurrence_length) + this->cooccurrence = (float*)realloc(this->cooccurrence, cooccurrence_lengthT * sizeof(float)); + offset += 3; + cooccurrence_length = cooccurrence_lengthT; + for( uint8_t i = 0; i < cooccurrence_length; i++){ + union { + float real; + uint32_t base; + } u_st_cooccurrence; + u_st_cooccurrence.base = 0; + u_st_cooccurrence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_cooccurrence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_cooccurrence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_cooccurrence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_cooccurrence = u_st_cooccurrence.real; + offset += sizeof(this->st_cooccurrence); + memcpy( &(this->cooccurrence[i]), &(this->st_cooccurrence), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "object_recognition_msgs/RecognizedObjectArray"; }; + const char * getMD5(){ return "bad6b1546b9ebcabb49fb3b858d78964"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/Table.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_object_recognition_msgs_Table_h +#define _ROS_object_recognition_msgs_Table_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Point.h" + +namespace object_recognition_msgs +{ + + class Table : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose pose; + uint8_t convex_hull_length; + geometry_msgs::Point st_convex_hull; + geometry_msgs::Point * convex_hull; + + Table(): + header(), + pose(), + convex_hull_length(0), convex_hull(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + *(outbuffer + offset++) = convex_hull_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < convex_hull_length; i++){ + offset += this->convex_hull[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + uint8_t convex_hull_lengthT = *(inbuffer + offset++); + if(convex_hull_lengthT > convex_hull_length) + this->convex_hull = (geometry_msgs::Point*)realloc(this->convex_hull, convex_hull_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + convex_hull_length = convex_hull_lengthT; + for( uint8_t i = 0; i < convex_hull_length; i++){ + offset += this->st_convex_hull.deserialize(inbuffer + offset); + memcpy( &(this->convex_hull[i]), &(this->st_convex_hull), sizeof(geometry_msgs::Point)); + } + return offset; + } + + const char * getType(){ return "object_recognition_msgs/Table"; }; + const char * getMD5(){ return "39efebc7d51e44bd2d72f2df6c7823a2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/object_recognition_msgs/TableArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_object_recognition_msgs_TableArray_h +#define _ROS_object_recognition_msgs_TableArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "object_recognition_msgs/Table.h" + +namespace object_recognition_msgs +{ + + class TableArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t tables_length; + object_recognition_msgs::Table st_tables; + object_recognition_msgs::Table * tables; + + TableArray(): + header(), + tables_length(0), tables(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = tables_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tables_length; i++){ + offset += this->tables[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t tables_lengthT = *(inbuffer + offset++); + if(tables_lengthT > tables_length) + this->tables = (object_recognition_msgs::Table*)realloc(this->tables, tables_lengthT * sizeof(object_recognition_msgs::Table)); + offset += 3; + tables_length = tables_lengthT; + for( uint8_t i = 0; i < tables_length; i++){ + offset += this->st_tables.deserialize(inbuffer + offset); + memcpy( &(this->tables[i]), &(this->st_tables), sizeof(object_recognition_msgs::Table)); + } + return offset; + } + + const char * getType(){ return "object_recognition_msgs/TableArray"; }; + const char * getMD5(){ return "d1c853e5acd0ed273eb6682dc01ab428"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/octomap_msgs/BoundingBoxQuery.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_SERVICE_BoundingBoxQuery_h +#define _ROS_SERVICE_BoundingBoxQuery_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Point.h" + +namespace octomap_msgs +{ + +static const char BOUNDINGBOXQUERY[] = "octomap_msgs/BoundingBoxQuery"; + + class BoundingBoxQueryRequest : public ros::Msg + { + public: + geometry_msgs::Point min; + geometry_msgs::Point max; + + BoundingBoxQueryRequest(): + min(), + max() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->min.serialize(outbuffer + offset); + offset += this->max.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->min.deserialize(inbuffer + offset); + offset += this->max.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return BOUNDINGBOXQUERY; }; + const char * getMD5(){ return "93aa3d73b866f04880927745f4aab303"; }; + + }; + + class BoundingBoxQueryResponse : public ros::Msg + { + public: + + BoundingBoxQueryResponse() + { + } + + 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 BOUNDINGBOXQUERY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class BoundingBoxQuery { + public: + typedef BoundingBoxQueryRequest Request; + typedef BoundingBoxQueryResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/octomap_msgs/GetOctomap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_SERVICE_GetOctomap_h +#define _ROS_SERVICE_GetOctomap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "octomap_msgs/Octomap.h" + +namespace octomap_msgs +{ + +static const char GETOCTOMAP[] = "octomap_msgs/GetOctomap"; + + class GetOctomapRequest : public ros::Msg + { + public: + + GetOctomapRequest() + { + } + + 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 GETOCTOMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetOctomapResponse : public ros::Msg + { + public: + octomap_msgs::Octomap map; + + GetOctomapResponse(): + map() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETOCTOMAP; }; + const char * getMD5(){ return "be9d2869d24fe40d6bc21ac21f6bb2c5"; }; + + }; + + class GetOctomap { + public: + typedef GetOctomapRequest Request; + typedef GetOctomapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/octomap_msgs/Octomap.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,113 @@ +#ifndef _ROS_octomap_msgs_Octomap_h +#define _ROS_octomap_msgs_Octomap_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace octomap_msgs +{ + + class Octomap : public ros::Msg + { + public: + std_msgs::Header header; + bool binary; + const char* id; + float resolution; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + Octomap(): + header(), + binary(0), + id(""), + resolution(0), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_binary; + u_binary.real = this->binary; + *(outbuffer + offset + 0) = (u_binary.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->binary); + uint32_t length_id = strlen(this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + offset += serializeAvrFloat64(outbuffer + offset, this->resolution); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_binary; + u_binary.base = 0; + u_binary.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->binary = u_binary.real; + offset += sizeof(this->binary); + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->resolution)); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "octomap_msgs/Octomap"; }; + const char * getMD5(){ return "9a45536b45c5e409cd49f04bb2d9999f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/octomap_msgs/OctomapWithPose.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_octomap_msgs_OctomapWithPose_h +#define _ROS_octomap_msgs_OctomapWithPose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "octomap_msgs/Octomap.h" + +namespace octomap_msgs +{ + + class OctomapWithPose : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose origin; + octomap_msgs::Octomap octomap; + + OctomapWithPose(): + header(), + origin(), + octomap() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->origin.serialize(outbuffer + offset); + offset += this->octomap.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->origin.deserialize(inbuffer + offset); + offset += this->octomap.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "octomap_msgs/OctomapWithPose"; }; + const char * getMD5(){ return "20b380aca6a508a657e95526cddaf618"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pcl_msgs/ModelCoefficients.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_pcl_msgs_ModelCoefficients_h +#define _ROS_pcl_msgs_ModelCoefficients_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace pcl_msgs +{ + + class ModelCoefficients : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t values_length; + float st_values; + float * values; + + ModelCoefficients(): + header(), + values_length(0), values(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_valuesi; + u_valuesi.real = this->values[i]; + *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->values[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t values_lengthT = *(inbuffer + offset++); + if(values_lengthT > values_length) + this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); + offset += 3; + values_length = values_lengthT; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_st_values; + u_st_values.base = 0; + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_values = u_st_values.real; + offset += sizeof(this->st_values); + memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "pcl_msgs/ModelCoefficients"; }; + const char * getMD5(){ return "ca27dea75e72cb894cd36f9e5005e93e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pcl_msgs/PointIndices.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_pcl_msgs_PointIndices_h +#define _ROS_pcl_msgs_PointIndices_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace pcl_msgs +{ + + class PointIndices : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t indices_length; + int32_t st_indices; + int32_t * indices; + + PointIndices(): + header(), + indices_length(0), indices(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = indices_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < indices_length; i++){ + union { + int32_t real; + uint32_t base; + } u_indicesi; + u_indicesi.real = this->indices[i]; + *(outbuffer + offset + 0) = (u_indicesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_indicesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_indicesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_indicesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->indices[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t indices_lengthT = *(inbuffer + offset++); + if(indices_lengthT > indices_length) + this->indices = (int32_t*)realloc(this->indices, indices_lengthT * sizeof(int32_t)); + offset += 3; + indices_length = indices_lengthT; + for( uint8_t i = 0; i < indices_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_indices; + u_st_indices.base = 0; + u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_indices.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_indices = u_st_indices.real; + offset += sizeof(this->st_indices); + memcpy( &(this->indices[i]), &(this->st_indices), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "pcl_msgs/PointIndices"; }; + const char * getMD5(){ return "458c7998b7eaf99908256472e273b3d4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pcl_msgs/PolygonMesh.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_pcl_msgs_PolygonMesh_h +#define _ROS_pcl_msgs_PolygonMesh_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/PointCloud2.h" +#include "pcl_msgs/Vertices.h" + +namespace pcl_msgs +{ + + class PolygonMesh : public ros::Msg + { + public: + std_msgs::Header header; + sensor_msgs::PointCloud2 cloud; + uint8_t polygons_length; + pcl_msgs::Vertices st_polygons; + pcl_msgs::Vertices * polygons; + + PolygonMesh(): + header(), + cloud(), + polygons_length(0), polygons(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->cloud.serialize(outbuffer + offset); + *(outbuffer + offset++) = polygons_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < polygons_length; i++){ + offset += this->polygons[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->cloud.deserialize(inbuffer + offset); + uint8_t polygons_lengthT = *(inbuffer + offset++); + if(polygons_lengthT > polygons_length) + this->polygons = (pcl_msgs::Vertices*)realloc(this->polygons, polygons_lengthT * sizeof(pcl_msgs::Vertices)); + offset += 3; + polygons_length = polygons_lengthT; + for( uint8_t i = 0; i < polygons_length; i++){ + offset += this->st_polygons.deserialize(inbuffer + offset); + memcpy( &(this->polygons[i]), &(this->st_polygons), sizeof(pcl_msgs::Vertices)); + } + return offset; + } + + const char * getType(){ return "pcl_msgs/PolygonMesh"; }; + const char * getMD5(){ return "45a5fc6ad2cde8489600a790acc9a38a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pcl_msgs/Vertices.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,66 @@ +#ifndef _ROS_pcl_msgs_Vertices_h +#define _ROS_pcl_msgs_Vertices_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pcl_msgs +{ + + class Vertices : public ros::Msg + { + public: + uint8_t vertices_length; + uint32_t st_vertices; + uint32_t * vertices; + + Vertices(): + vertices_length(0), vertices(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = vertices_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < vertices_length; i++){ + *(outbuffer + offset + 0) = (this->vertices[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->vertices[i] >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->vertices[i] >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->vertices[i] >> (8 * 3)) & 0xFF; + offset += sizeof(this->vertices[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t vertices_lengthT = *(inbuffer + offset++); + if(vertices_lengthT > vertices_length) + this->vertices = (uint32_t*)realloc(this->vertices, vertices_lengthT * sizeof(uint32_t)); + offset += 3; + vertices_length = vertices_lengthT; + for( uint8_t i = 0; i < vertices_length; i++){ + this->st_vertices = ((uint32_t) (*(inbuffer + offset))); + this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->st_vertices); + memcpy( &(this->vertices[i]), &(this->st_vertices), sizeof(uint32_t)); + } + return offset; + } + + const char * getType(){ return "pcl_msgs/Vertices"; }; + const char * getMD5(){ return "39bd7b1c23763ddd1b882b97cb7cfe11"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/polled_camera/GetPolledImage.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,195 @@ +#ifndef _ROS_SERVICE_GetPolledImage_h +#define _ROS_SERVICE_GetPolledImage_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/RegionOfInterest.h" +#include "ros/duration.h" +#include "ros/time.h" + +namespace polled_camera +{ + +static const char GETPOLLEDIMAGE[] = "polled_camera/GetPolledImage"; + + class GetPolledImageRequest : public ros::Msg + { + public: + const char* response_namespace; + ros::Duration timeout; + uint32_t binning_x; + uint32_t binning_y; + sensor_msgs::RegionOfInterest roi; + + GetPolledImageRequest(): + response_namespace(""), + timeout(), + binning_x(0), + binning_y(0), + roi() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_response_namespace = strlen(this->response_namespace); + memcpy(outbuffer + offset, &length_response_namespace, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->response_namespace, length_response_namespace); + offset += length_response_namespace; + *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.sec); + *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.nsec); + *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_x); + *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_y); + offset += this->roi.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_response_namespace; + memcpy(&length_response_namespace, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_response_namespace; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_response_namespace-1]=0; + this->response_namespace = (char *)(inbuffer + offset-1); + offset += length_response_namespace; + this->timeout.sec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.sec); + this->timeout.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.nsec); + this->binning_x = ((uint32_t) (*(inbuffer + offset))); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_x); + this->binning_y = ((uint32_t) (*(inbuffer + offset))); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_y); + offset += this->roi.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPOLLEDIMAGE; }; + const char * getMD5(){ return "c77ed43e530fd48e9e7a2a93845e154c"; }; + + }; + + class GetPolledImageResponse : public ros::Msg + { + public: + bool success; + const char* status_message; + ros::Time stamp; + + GetPolledImageResponse(): + success(0), + status_message(""), + stamp() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen(this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + return offset; + } + + const char * getType(){ return GETPOLLEDIMAGE; }; + const char * getMD5(){ return "dbf1f851bc511800e6129ccd5a3542ab"; }; + + }; + + class GetPolledImage { + public: + typedef GetPolledImageRequest Request; + typedef GetPolledImageResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/ActuatorStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,283 @@ +#ifndef _ROS_pr2_mechanism_msgs_ActuatorStatistics_h +#define _ROS_pr2_mechanism_msgs_ActuatorStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace pr2_mechanism_msgs +{ + + class ActuatorStatistics : public ros::Msg + { + public: + const char* name; + int32_t device_id; + ros::Time timestamp; + int32_t encoder_count; + float encoder_offset; + float position; + float encoder_velocity; + float velocity; + bool calibration_reading; + bool calibration_rising_edge_valid; + bool calibration_falling_edge_valid; + float last_calibration_rising_edge; + float last_calibration_falling_edge; + bool is_enabled; + bool halted; + float last_commanded_current; + float last_commanded_effort; + float last_executed_current; + float last_executed_effort; + float last_measured_current; + float last_measured_effort; + float motor_voltage; + int32_t num_encoder_errors; + + ActuatorStatistics(): + name(""), + device_id(0), + timestamp(), + encoder_count(0), + encoder_offset(0), + position(0), + encoder_velocity(0), + velocity(0), + calibration_reading(0), + calibration_rising_edge_valid(0), + calibration_falling_edge_valid(0), + last_calibration_rising_edge(0), + last_calibration_falling_edge(0), + is_enabled(0), + halted(0), + last_commanded_current(0), + last_commanded_effort(0), + last_executed_current(0), + last_executed_effort(0), + last_measured_current(0), + last_measured_effort(0), + motor_voltage(0), + num_encoder_errors(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + union { + int32_t real; + uint32_t base; + } u_device_id; + u_device_id.real = this->device_id; + *(outbuffer + offset + 0) = (u_device_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_device_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_device_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_device_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->device_id); + *(outbuffer + offset + 0) = (this->timestamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.sec); + *(outbuffer + offset + 0) = (this->timestamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.nsec); + union { + int32_t real; + uint32_t base; + } u_encoder_count; + u_encoder_count.real = this->encoder_count; + *(outbuffer + offset + 0) = (u_encoder_count.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_encoder_count.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_encoder_count.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_encoder_count.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->encoder_count); + offset += serializeAvrFloat64(outbuffer + offset, this->encoder_offset); + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->encoder_velocity); + offset += serializeAvrFloat64(outbuffer + offset, this->velocity); + union { + bool real; + uint8_t base; + } u_calibration_reading; + u_calibration_reading.real = this->calibration_reading; + *(outbuffer + offset + 0) = (u_calibration_reading.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->calibration_reading); + union { + bool real; + uint8_t base; + } u_calibration_rising_edge_valid; + u_calibration_rising_edge_valid.real = this->calibration_rising_edge_valid; + *(outbuffer + offset + 0) = (u_calibration_rising_edge_valid.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->calibration_rising_edge_valid); + union { + bool real; + uint8_t base; + } u_calibration_falling_edge_valid; + u_calibration_falling_edge_valid.real = this->calibration_falling_edge_valid; + *(outbuffer + offset + 0) = (u_calibration_falling_edge_valid.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->calibration_falling_edge_valid); + offset += serializeAvrFloat64(outbuffer + offset, this->last_calibration_rising_edge); + offset += serializeAvrFloat64(outbuffer + offset, this->last_calibration_falling_edge); + union { + bool real; + uint8_t base; + } u_is_enabled; + u_is_enabled.real = this->is_enabled; + *(outbuffer + offset + 0) = (u_is_enabled.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_enabled); + union { + bool real; + uint8_t base; + } u_halted; + u_halted.real = this->halted; + *(outbuffer + offset + 0) = (u_halted.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->halted); + offset += serializeAvrFloat64(outbuffer + offset, this->last_commanded_current); + offset += serializeAvrFloat64(outbuffer + offset, this->last_commanded_effort); + offset += serializeAvrFloat64(outbuffer + offset, this->last_executed_current); + offset += serializeAvrFloat64(outbuffer + offset, this->last_executed_effort); + offset += serializeAvrFloat64(outbuffer + offset, this->last_measured_current); + offset += serializeAvrFloat64(outbuffer + offset, this->last_measured_effort); + offset += serializeAvrFloat64(outbuffer + offset, this->motor_voltage); + union { + int32_t real; + uint32_t base; + } u_num_encoder_errors; + u_num_encoder_errors.real = this->num_encoder_errors; + *(outbuffer + offset + 0) = (u_num_encoder_errors.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_num_encoder_errors.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_num_encoder_errors.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_num_encoder_errors.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->num_encoder_errors); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + union { + int32_t real; + uint32_t base; + } u_device_id; + u_device_id.base = 0; + u_device_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_device_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_device_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_device_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->device_id = u_device_id.real; + offset += sizeof(this->device_id); + this->timestamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.sec); + this->timestamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.nsec); + union { + int32_t real; + uint32_t base; + } u_encoder_count; + u_encoder_count.base = 0; + u_encoder_count.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_encoder_count.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_encoder_count.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_encoder_count.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->encoder_count = u_encoder_count.real; + offset += sizeof(this->encoder_count); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->encoder_offset)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->encoder_velocity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->velocity)); + union { + bool real; + uint8_t base; + } u_calibration_reading; + u_calibration_reading.base = 0; + u_calibration_reading.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->calibration_reading = u_calibration_reading.real; + offset += sizeof(this->calibration_reading); + union { + bool real; + uint8_t base; + } u_calibration_rising_edge_valid; + u_calibration_rising_edge_valid.base = 0; + u_calibration_rising_edge_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->calibration_rising_edge_valid = u_calibration_rising_edge_valid.real; + offset += sizeof(this->calibration_rising_edge_valid); + union { + bool real; + uint8_t base; + } u_calibration_falling_edge_valid; + u_calibration_falling_edge_valid.base = 0; + u_calibration_falling_edge_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->calibration_falling_edge_valid = u_calibration_falling_edge_valid.real; + offset += sizeof(this->calibration_falling_edge_valid); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_calibration_rising_edge)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_calibration_falling_edge)); + union { + bool real; + uint8_t base; + } u_is_enabled; + u_is_enabled.base = 0; + u_is_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_enabled = u_is_enabled.real; + offset += sizeof(this->is_enabled); + union { + bool real; + uint8_t base; + } u_halted; + u_halted.base = 0; + u_halted.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->halted = u_halted.real; + offset += sizeof(this->halted); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_commanded_current)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_commanded_effort)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_executed_current)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_executed_effort)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_measured_current)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->last_measured_effort)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->motor_voltage)); + union { + int32_t real; + uint32_t base; + } u_num_encoder_errors; + u_num_encoder_errors.base = 0; + u_num_encoder_errors.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_num_encoder_errors.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_num_encoder_errors.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_num_encoder_errors.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->num_encoder_errors = u_num_encoder_errors.real; + offset += sizeof(this->num_encoder_errors); + return offset; + } + + const char * getType(){ return "pr2_mechanism_msgs/ActuatorStatistics"; }; + const char * getMD5(){ return "c37184273b29627de29382f1d3670175"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/ControllerStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,206 @@ +#ifndef _ROS_pr2_mechanism_msgs_ControllerStatistics_h +#define _ROS_pr2_mechanism_msgs_ControllerStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "ros/duration.h" + +namespace pr2_mechanism_msgs +{ + + class ControllerStatistics : public ros::Msg + { + public: + const char* name; + ros::Time timestamp; + bool running; + ros::Duration max_time; + ros::Duration mean_time; + ros::Duration variance_time; + int32_t num_control_loop_overruns; + ros::Time time_last_control_loop_overrun; + + ControllerStatistics(): + name(""), + timestamp(), + running(0), + max_time(), + mean_time(), + variance_time(), + num_control_loop_overruns(0), + time_last_control_loop_overrun() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset + 0) = (this->timestamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.sec); + *(outbuffer + offset + 0) = (this->timestamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.nsec); + union { + bool real; + uint8_t base; + } u_running; + u_running.real = this->running; + *(outbuffer + offset + 0) = (u_running.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->running); + *(outbuffer + offset + 0) = (this->max_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->max_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->max_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->max_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_time.sec); + *(outbuffer + offset + 0) = (this->max_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->max_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->max_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->max_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_time.nsec); + *(outbuffer + offset + 0) = (this->mean_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->mean_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->mean_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->mean_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean_time.sec); + *(outbuffer + offset + 0) = (this->mean_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->mean_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->mean_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->mean_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->mean_time.nsec); + *(outbuffer + offset + 0) = (this->variance_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->variance_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->variance_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->variance_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->variance_time.sec); + *(outbuffer + offset + 0) = (this->variance_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->variance_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->variance_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->variance_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->variance_time.nsec); + union { + int32_t real; + uint32_t base; + } u_num_control_loop_overruns; + u_num_control_loop_overruns.real = this->num_control_loop_overruns; + *(outbuffer + offset + 0) = (u_num_control_loop_overruns.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_num_control_loop_overruns.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_num_control_loop_overruns.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_num_control_loop_overruns.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->num_control_loop_overruns); + *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_last_control_loop_overrun.sec); + *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_last_control_loop_overrun.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + this->timestamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.sec); + this->timestamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.nsec); + union { + bool real; + uint8_t base; + } u_running; + u_running.base = 0; + u_running.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->running = u_running.real; + offset += sizeof(this->running); + this->max_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->max_time.sec); + this->max_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->max_time.nsec); + this->mean_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->mean_time.sec); + this->mean_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->mean_time.nsec); + this->variance_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->variance_time.sec); + this->variance_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->variance_time.nsec); + union { + int32_t real; + uint32_t base; + } u_num_control_loop_overruns; + u_num_control_loop_overruns.base = 0; + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->num_control_loop_overruns = u_num_control_loop_overruns.real; + offset += sizeof(this->num_control_loop_overruns); + this->time_last_control_loop_overrun.sec = ((uint32_t) (*(inbuffer + offset))); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_last_control_loop_overrun.sec); + this->time_last_control_loop_overrun.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_last_control_loop_overrun.nsec); + return offset; + } + + const char * getType(){ return "pr2_mechanism_msgs/ControllerStatistics"; }; + const char * getMD5(){ return "6d15d137eea402018e3c7c8dbecd4b95"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/JointStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,147 @@ +#ifndef _ROS_pr2_mechanism_msgs_JointStatistics_h +#define _ROS_pr2_mechanism_msgs_JointStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace pr2_mechanism_msgs +{ + + class JointStatistics : public ros::Msg + { + public: + const char* name; + ros::Time timestamp; + float position; + float velocity; + float measured_effort; + float commanded_effort; + bool is_calibrated; + bool violated_limits; + float odometer; + float min_position; + float max_position; + float max_abs_velocity; + float max_abs_effort; + + JointStatistics(): + name(""), + timestamp(), + position(0), + velocity(0), + measured_effort(0), + commanded_effort(0), + is_calibrated(0), + violated_limits(0), + odometer(0), + min_position(0), + max_position(0), + max_abs_velocity(0), + max_abs_effort(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset + 0) = (this->timestamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.sec); + *(outbuffer + offset + 0) = (this->timestamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timestamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timestamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timestamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timestamp.nsec); + offset += serializeAvrFloat64(outbuffer + offset, this->position); + offset += serializeAvrFloat64(outbuffer + offset, this->velocity); + offset += serializeAvrFloat64(outbuffer + offset, this->measured_effort); + offset += serializeAvrFloat64(outbuffer + offset, this->commanded_effort); + 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); + union { + bool real; + uint8_t base; + } u_violated_limits; + u_violated_limits.real = this->violated_limits; + *(outbuffer + offset + 0) = (u_violated_limits.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->violated_limits); + offset += serializeAvrFloat64(outbuffer + offset, this->odometer); + offset += serializeAvrFloat64(outbuffer + offset, this->min_position); + offset += serializeAvrFloat64(outbuffer + offset, this->max_position); + offset += serializeAvrFloat64(outbuffer + offset, this->max_abs_velocity); + offset += serializeAvrFloat64(outbuffer + offset, this->max_abs_effort); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + this->timestamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.sec); + this->timestamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timestamp.nsec); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->velocity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->measured_effort)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->commanded_effort)); + 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); + union { + bool real; + uint8_t base; + } u_violated_limits; + u_violated_limits.base = 0; + u_violated_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->violated_limits = u_violated_limits.real; + offset += sizeof(this->violated_limits); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->odometer)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_position)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_abs_velocity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_abs_effort)); + return offset; + } + + const char * getType(){ return "pr2_mechanism_msgs/JointStatistics"; }; + const char * getMD5(){ return "90fdc8acbce5bc783d8b4aec49af6590"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/ListControllerTypes.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_SERVICE_ListControllerTypes_h +#define _ROS_SERVICE_ListControllerTypes_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char LISTCONTROLLERTYPES[] = "pr2_mechanism_msgs/ListControllerTypes"; + + class ListControllerTypesRequest : public ros::Msg + { + public: + + ListControllerTypesRequest() + { + } + + 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 LISTCONTROLLERTYPES; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class ListControllerTypesResponse : public ros::Msg + { + public: + uint8_t types_length; + char* st_types; + char* * types; + + ListControllerTypesResponse(): + types_length(0), types(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = types_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < types_length; i++){ + uint32_t length_typesi = strlen(this->types[i]); + memcpy(outbuffer + offset, &length_typesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->types[i], length_typesi); + offset += length_typesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t types_lengthT = *(inbuffer + offset++); + if(types_lengthT > types_length) + this->types = (char**)realloc(this->types, types_lengthT * sizeof(char*)); + offset += 3; + types_length = types_lengthT; + for( uint8_t i = 0; i < types_length; i++){ + uint32_t length_st_types; + memcpy(&length_st_types, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_types; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_types-1]=0; + this->st_types = (char *)(inbuffer + offset-1); + offset += length_st_types; + memcpy( &(this->types[i]), &(this->st_types), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return LISTCONTROLLERTYPES; }; + const char * getMD5(){ return "80aee506387f88339842e9a93044c959"; }; + + }; + + class ListControllerTypes { + public: + typedef ListControllerTypesRequest Request; + typedef ListControllerTypesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/ListControllers.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,135 @@ +#ifndef _ROS_SERVICE_ListControllers_h +#define _ROS_SERVICE_ListControllers_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char LISTCONTROLLERS[] = "pr2_mechanism_msgs/ListControllers"; + + class ListControllersRequest : public ros::Msg + { + public: + + ListControllersRequest() + { + } + + 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 LISTCONTROLLERS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class ListControllersResponse : public ros::Msg + { + public: + uint8_t controllers_length; + char* st_controllers; + char* * controllers; + uint8_t state_length; + char* st_state; + char* * state; + + ListControllersResponse(): + controllers_length(0), controllers(NULL), + state_length(0), state(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < controllers_length; i++){ + uint32_t length_controllersi = strlen(this->controllers[i]); + memcpy(outbuffer + offset, &length_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->controllers[i], length_controllersi); + offset += length_controllersi; + } + *(outbuffer + offset++) = state_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < state_length; i++){ + uint32_t length_statei = strlen(this->state[i]); + memcpy(outbuffer + offset, &length_statei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->state[i], length_statei); + offset += length_statei; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t controllers_lengthT = *(inbuffer + offset++); + if(controllers_lengthT > controllers_length) + this->controllers = (char**)realloc(this->controllers, controllers_lengthT * sizeof(char*)); + offset += 3; + controllers_length = controllers_lengthT; + for( uint8_t i = 0; i < controllers_length; i++){ + uint32_t length_st_controllers; + memcpy(&length_st_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_controllers-1]=0; + this->st_controllers = (char *)(inbuffer + offset-1); + offset += length_st_controllers; + memcpy( &(this->controllers[i]), &(this->st_controllers), sizeof(char*)); + } + uint8_t state_lengthT = *(inbuffer + offset++); + if(state_lengthT > state_length) + this->state = (char**)realloc(this->state, state_lengthT * sizeof(char*)); + offset += 3; + state_length = state_lengthT; + for( uint8_t i = 0; i < state_length; i++){ + uint32_t length_st_state; + memcpy(&length_st_state, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_state; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_state-1]=0; + this->st_state = (char *)(inbuffer + offset-1); + offset += length_st_state; + memcpy( &(this->state[i]), &(this->st_state), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return LISTCONTROLLERS; }; + const char * getMD5(){ return "39c8d39516aed5c7d76284ac06c220e5"; }; + + }; + + class ListControllers { + public: + typedef ListControllersRequest Request; + typedef ListControllersResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/LoadController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_LoadController_h +#define _ROS_SERVICE_LoadController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char LOADCONTROLLER[] = "pr2_mechanism_msgs/LoadController"; + + class LoadControllerRequest : public ros::Msg + { + public: + const char* name; + + LoadControllerRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class LoadControllerResponse : public ros::Msg + { + public: + bool ok; + + LoadControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class LoadController { + public: + typedef LoadControllerRequest Request; + typedef LoadControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/MechanismStatistics.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,106 @@ +#ifndef _ROS_pr2_mechanism_msgs_MechanismStatistics_h +#define _ROS_pr2_mechanism_msgs_MechanismStatistics_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "pr2_mechanism_msgs/ActuatorStatistics.h" +#include "pr2_mechanism_msgs/JointStatistics.h" +#include "pr2_mechanism_msgs/ControllerStatistics.h" + +namespace pr2_mechanism_msgs +{ + + class MechanismStatistics : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t actuator_statistics_length; + pr2_mechanism_msgs::ActuatorStatistics st_actuator_statistics; + pr2_mechanism_msgs::ActuatorStatistics * actuator_statistics; + uint8_t joint_statistics_length; + pr2_mechanism_msgs::JointStatistics st_joint_statistics; + pr2_mechanism_msgs::JointStatistics * joint_statistics; + uint8_t controller_statistics_length; + pr2_mechanism_msgs::ControllerStatistics st_controller_statistics; + pr2_mechanism_msgs::ControllerStatistics * controller_statistics; + + MechanismStatistics(): + header(), + actuator_statistics_length(0), actuator_statistics(NULL), + joint_statistics_length(0), joint_statistics(NULL), + controller_statistics_length(0), controller_statistics(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = actuator_statistics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < actuator_statistics_length; i++){ + offset += this->actuator_statistics[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = joint_statistics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_statistics_length; i++){ + offset += this->joint_statistics[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = controller_statistics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < controller_statistics_length; i++){ + offset += this->controller_statistics[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t actuator_statistics_lengthT = *(inbuffer + offset++); + if(actuator_statistics_lengthT > actuator_statistics_length) + this->actuator_statistics = (pr2_mechanism_msgs::ActuatorStatistics*)realloc(this->actuator_statistics, actuator_statistics_lengthT * sizeof(pr2_mechanism_msgs::ActuatorStatistics)); + offset += 3; + actuator_statistics_length = actuator_statistics_lengthT; + for( uint8_t i = 0; i < actuator_statistics_length; i++){ + offset += this->st_actuator_statistics.deserialize(inbuffer + offset); + memcpy( &(this->actuator_statistics[i]), &(this->st_actuator_statistics), sizeof(pr2_mechanism_msgs::ActuatorStatistics)); + } + uint8_t joint_statistics_lengthT = *(inbuffer + offset++); + if(joint_statistics_lengthT > joint_statistics_length) + this->joint_statistics = (pr2_mechanism_msgs::JointStatistics*)realloc(this->joint_statistics, joint_statistics_lengthT * sizeof(pr2_mechanism_msgs::JointStatistics)); + offset += 3; + joint_statistics_length = joint_statistics_lengthT; + for( uint8_t i = 0; i < joint_statistics_length; i++){ + offset += this->st_joint_statistics.deserialize(inbuffer + offset); + memcpy( &(this->joint_statistics[i]), &(this->st_joint_statistics), sizeof(pr2_mechanism_msgs::JointStatistics)); + } + uint8_t controller_statistics_lengthT = *(inbuffer + offset++); + if(controller_statistics_lengthT > controller_statistics_length) + this->controller_statistics = (pr2_mechanism_msgs::ControllerStatistics*)realloc(this->controller_statistics, controller_statistics_lengthT * sizeof(pr2_mechanism_msgs::ControllerStatistics)); + offset += 3; + controller_statistics_length = controller_statistics_lengthT; + for( uint8_t i = 0; i < controller_statistics_length; i++){ + offset += this->st_controller_statistics.deserialize(inbuffer + offset); + memcpy( &(this->controller_statistics[i]), &(this->st_controller_statistics), sizeof(pr2_mechanism_msgs::ControllerStatistics)); + } + return offset; + } + + const char * getType(){ return "pr2_mechanism_msgs/MechanismStatistics"; }; + const char * getMD5(){ return "b4a99069393681672c01f8c823458e04"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/ReloadControllerLibraries.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,105 @@ +#ifndef _ROS_SERVICE_ReloadControllerLibraries_h +#define _ROS_SERVICE_ReloadControllerLibraries_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char RELOADCONTROLLERLIBRARIES[] = "pr2_mechanism_msgs/ReloadControllerLibraries"; + + class ReloadControllerLibrariesRequest : public ros::Msg + { + public: + bool force_kill; + + ReloadControllerLibrariesRequest(): + force_kill(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_force_kill; + u_force_kill.real = this->force_kill; + *(outbuffer + offset + 0) = (u_force_kill.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->force_kill); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_force_kill; + u_force_kill.base = 0; + u_force_kill.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->force_kill = u_force_kill.real; + offset += sizeof(this->force_kill); + return offset; + } + + const char * getType(){ return RELOADCONTROLLERLIBRARIES; }; + const char * getMD5(){ return "18442b59be9479097f11c543bddbac62"; }; + + }; + + class ReloadControllerLibrariesResponse : public ros::Msg + { + public: + bool ok; + + ReloadControllerLibrariesResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return RELOADCONTROLLERLIBRARIES; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class ReloadControllerLibraries { + public: + typedef ReloadControllerLibrariesRequest Request; + typedef ReloadControllerLibrariesResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,177 @@ +#ifndef _ROS_SERVICE_SwitchController_h +#define _ROS_SERVICE_SwitchController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char SWITCHCONTROLLER[] = "pr2_mechanism_msgs/SwitchController"; + + class SwitchControllerRequest : public ros::Msg + { + public: + uint8_t start_controllers_length; + char* st_start_controllers; + char* * start_controllers; + uint8_t stop_controllers_length; + char* st_stop_controllers; + char* * stop_controllers; + int32_t strictness; + enum { BEST_EFFORT = 1 }; + enum { STRICT = 2 }; + + SwitchControllerRequest(): + start_controllers_length(0), start_controllers(NULL), + stop_controllers_length(0), stop_controllers(NULL), + strictness(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = start_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_start_controllersi = strlen(this->start_controllers[i]); + memcpy(outbuffer + offset, &length_start_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->start_controllers[i], length_start_controllersi); + offset += length_start_controllersi; + } + *(outbuffer + offset++) = stop_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_stop_controllersi = strlen(this->stop_controllers[i]); + memcpy(outbuffer + offset, &length_stop_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->stop_controllers[i], length_stop_controllersi); + offset += length_stop_controllersi; + } + union { + int32_t real; + uint32_t base; + } u_strictness; + u_strictness.real = this->strictness; + *(outbuffer + offset + 0) = (u_strictness.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_strictness.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_strictness.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_strictness.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->strictness); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t start_controllers_lengthT = *(inbuffer + offset++); + if(start_controllers_lengthT > start_controllers_length) + this->start_controllers = (char**)realloc(this->start_controllers, start_controllers_lengthT * sizeof(char*)); + offset += 3; + start_controllers_length = start_controllers_lengthT; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_st_start_controllers; + memcpy(&length_st_start_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_start_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_start_controllers-1]=0; + this->st_start_controllers = (char *)(inbuffer + offset-1); + offset += length_st_start_controllers; + memcpy( &(this->start_controllers[i]), &(this->st_start_controllers), sizeof(char*)); + } + uint8_t stop_controllers_lengthT = *(inbuffer + offset++); + if(stop_controllers_lengthT > stop_controllers_length) + this->stop_controllers = (char**)realloc(this->stop_controllers, stop_controllers_lengthT * sizeof(char*)); + offset += 3; + stop_controllers_length = stop_controllers_lengthT; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_st_stop_controllers; + memcpy(&length_st_stop_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_stop_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_stop_controllers-1]=0; + this->st_stop_controllers = (char *)(inbuffer + offset-1); + offset += length_st_stop_controllers; + memcpy( &(this->stop_controllers[i]), &(this->st_stop_controllers), sizeof(char*)); + } + union { + int32_t real; + uint32_t base; + } u_strictness; + u_strictness.base = 0; + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_strictness.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->strictness = u_strictness.real; + offset += sizeof(this->strictness); + return offset; + } + + const char * getType(){ return SWITCHCONTROLLER; }; + const char * getMD5(){ return "434da54adc434a5af5743ed711fd6ba1"; }; + + }; + + class SwitchControllerResponse : public ros::Msg + { + public: + bool ok; + + SwitchControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return SWITCHCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class SwitchController { + public: + typedef SwitchControllerRequest Request; + typedef SwitchControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerAction_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "pr2_mechanism_msgs/SwitchControllerActionGoal.h" +#include "pr2_mechanism_msgs/SwitchControllerActionResult.h" +#include "pr2_mechanism_msgs/SwitchControllerActionFeedback.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerAction : public ros::Msg + { + public: + pr2_mechanism_msgs::SwitchControllerActionGoal action_goal; + pr2_mechanism_msgs::SwitchControllerActionResult action_result; + pr2_mechanism_msgs::SwitchControllerActionFeedback action_feedback; + + SwitchControllerAction(): + 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 "pr2_mechanism_msgs/SwitchControllerAction"; }; + const char * getMD5(){ return "c7b048ee44f1abe19d1dfae77332d13a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerActionFeedback_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "pr2_mechanism_msgs/SwitchControllerFeedback.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + pr2_mechanism_msgs::SwitchControllerFeedback feedback; + + SwitchControllerActionFeedback(): + 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 "pr2_mechanism_msgs/SwitchControllerActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerActionGoal_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "pr2_mechanism_msgs/SwitchControllerGoal.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + pr2_mechanism_msgs::SwitchControllerGoal goal; + + SwitchControllerActionGoal(): + 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 "pr2_mechanism_msgs/SwitchControllerActionGoal"; }; + const char * getMD5(){ return "c1a50547b620e7c8fc34420b6601a77a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerActionResult_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "pr2_mechanism_msgs/SwitchControllerResult.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + pr2_mechanism_msgs::SwitchControllerResult result; + + SwitchControllerActionResult(): + 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 "pr2_mechanism_msgs/SwitchControllerActionResult"; }; + const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerFeedback_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerFeedback : public ros::Msg + { + public: + + SwitchControllerFeedback() + { + } + + 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 "pr2_mechanism_msgs/SwitchControllerFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,102 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerGoal_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerGoal : public ros::Msg + { + public: + uint8_t start_controllers_length; + char* st_start_controllers; + char* * start_controllers; + uint8_t stop_controllers_length; + char* st_stop_controllers; + char* * stop_controllers; + + SwitchControllerGoal(): + start_controllers_length(0), start_controllers(NULL), + stop_controllers_length(0), stop_controllers(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = start_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_start_controllersi = strlen(this->start_controllers[i]); + memcpy(outbuffer + offset, &length_start_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->start_controllers[i], length_start_controllersi); + offset += length_start_controllersi; + } + *(outbuffer + offset++) = stop_controllers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_stop_controllersi = strlen(this->stop_controllers[i]); + memcpy(outbuffer + offset, &length_stop_controllersi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->stop_controllers[i], length_stop_controllersi); + offset += length_stop_controllersi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t start_controllers_lengthT = *(inbuffer + offset++); + if(start_controllers_lengthT > start_controllers_length) + this->start_controllers = (char**)realloc(this->start_controllers, start_controllers_lengthT * sizeof(char*)); + offset += 3; + start_controllers_length = start_controllers_lengthT; + for( uint8_t i = 0; i < start_controllers_length; i++){ + uint32_t length_st_start_controllers; + memcpy(&length_st_start_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_start_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_start_controllers-1]=0; + this->st_start_controllers = (char *)(inbuffer + offset-1); + offset += length_st_start_controllers; + memcpy( &(this->start_controllers[i]), &(this->st_start_controllers), sizeof(char*)); + } + uint8_t stop_controllers_lengthT = *(inbuffer + offset++); + if(stop_controllers_lengthT > stop_controllers_length) + this->stop_controllers = (char**)realloc(this->stop_controllers, stop_controllers_lengthT * sizeof(char*)); + offset += 3; + stop_controllers_length = stop_controllers_lengthT; + for( uint8_t i = 0; i < stop_controllers_length; i++){ + uint32_t length_st_stop_controllers; + memcpy(&length_st_stop_controllers, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_stop_controllers; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_stop_controllers-1]=0; + this->st_stop_controllers = (char *)(inbuffer + offset-1); + offset += length_st_stop_controllers; + memcpy( &(this->stop_controllers[i]), &(this->st_stop_controllers), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "pr2_mechanism_msgs/SwitchControllerGoal"; }; + const char * getMD5(){ return "c3f1879cbb2d6cd8732c0e031574dde5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/SwitchControllerResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_pr2_mechanism_msgs_SwitchControllerResult_h +#define _ROS_pr2_mechanism_msgs_SwitchControllerResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + + class SwitchControllerResult : public ros::Msg + { + public: + + SwitchControllerResult() + { + } + + 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 "pr2_mechanism_msgs/SwitchControllerResult"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pr2_mechanism_msgs/UnloadController.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_SERVICE_UnloadController_h +#define _ROS_SERVICE_UnloadController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace pr2_mechanism_msgs +{ + +static const char UNLOADCONTROLLER[] = "pr2_mechanism_msgs/UnloadController"; + + class UnloadControllerRequest : public ros::Msg + { + public: + const char* name; + + UnloadControllerRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return UNLOADCONTROLLER; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class UnloadControllerResponse : public ros::Msg + { + public: + bool ok; + + UnloadControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return UNLOADCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class UnloadController { + public: + typedef UnloadControllerRequest Request; + typedef UnloadControllerResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/robot_pose_ekf/GetStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_GetStatus_h +#define _ROS_SERVICE_GetStatus_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace robot_pose_ekf +{ + +static const char GETSTATUS[] = "robot_pose_ekf/GetStatus"; + + class GetStatusRequest : public ros::Msg + { + public: + + GetStatusRequest() + { + } + + 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 GETSTATUS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetStatusResponse : public ros::Msg + { + public: + const char* status; + + GetStatusResponse(): + status("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_status = strlen(this->status); + memcpy(outbuffer + offset, &length_status, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status, length_status); + offset += length_status; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_status; + memcpy(&length_status, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status-1]=0; + this->status = (char *)(inbuffer + offset-1); + offset += length_status; + return offset; + } + + const char * getType(){ return GETSTATUS; }; + const char * getMD5(){ return "4fe5af303955c287688e7347e9b00278"; }; + + }; + + class GetStatus { + public: + typedef GetStatusRequest Request; + typedef GetStatusResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,47 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_H +#define _ROS_H + +#include "ros/node_handle.h" +#include "MbedHardware.h" + +namespace ros +{ + typedef NodeHandle_<MbedHardware> NodeHandle; +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/duration.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_DURATION_H_ +#define _ROS_DURATION_H_ + +#include <math.h> + +namespace ros { + + void normalizeSecNSecSigned(long& sec, long& nsec); + + class Duration + { + public: + long sec, nsec; + + Duration() : sec(0), nsec(0) {} + Duration(long _sec, long _nsec) : sec(_sec), nsec(_nsec) + { + normalizeSecNSecSigned(sec, nsec); + } + + double toSec() const { return (double)sec + 1e-9*(double)nsec; }; + void fromSec(double t) { sec = (unsigned long) floor(t); nsec = (unsigned long) floor((t-sec) * 1e9); }; + + Duration& operator+=(const Duration &rhs); + Duration& operator-=(const Duration &rhs); + Duration& operator*=(double scale); + }; + +} + +#endif + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/msg.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,130 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_MSG_H_ +#define _ROS_MSG_H_ + +#include <stdint.h> + +namespace ros { + +/* Base Message Type */ +class Msg +{ +public: + virtual int serialize(unsigned char *outbuffer) const = 0; + virtual int deserialize(unsigned char *data) = 0; + virtual const char * getType() = 0; + virtual const char * getMD5() = 0; + + /** + * @brief This tricky function handles promoting a 32bit float to a 64bit + * double, so that AVR can publish messages containing float64 + * fields, despite AVV having no native support for double. + * + * @param[out] outbuffer pointer for buffer to serialize to. + * @param[in] f value to serialize. + * + * @return number of bytes to advance the buffer pointer. + * + */ + static int serializeAvrFloat64(unsigned char* outbuffer, const float f) + { + const int32_t* val = (int32_t*) &f; + int32_t exp = ((*val >> 23) & 255); + if (exp != 0) + { + exp += 1023 - 127; + } + + int32_t sig = *val; + *(outbuffer++) = 0; + *(outbuffer++) = 0; + *(outbuffer++) = 0; + *(outbuffer++) = (sig << 5) & 0xff; + *(outbuffer++) = (sig >> 3) & 0xff; + *(outbuffer++) = (sig >> 11) & 0xff; + *(outbuffer++) = ((exp << 4) & 0xF0) | ((sig >> 19) & 0x0F); + *(outbuffer++) = (exp >> 4) & 0x7F; + + // Mark negative bit as necessary. + if (f < 0) + { + *(outbuffer - 1) |= 0x80; + } + + return 8; + } + + /** + * @brief This tricky function handles demoting a 64bit double to a + * 32bit float, so that AVR can understand messages containing + * float64 fields, despite AVR having no native support for double. + * + * @param[in] inbuffer pointer for buffer to deserialize from. + * @param[out] f pointer to place the deserialized value in. + * + * @return number of bytes to advance the buffer pointer. + */ + static int deserializeAvrFloat64(const unsigned char* inbuffer, float* f) + { + uint32_t* val = (uint32_t*)f; + inbuffer += 3; + + // Copy truncated mantissa. + *val = ((uint32_t)(*(inbuffer++)) >> 5 & 0x07); + *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 3; + *val |= ((uint32_t)(*(inbuffer++)) & 0xff) << 11; + *val |= ((uint32_t)(*inbuffer) & 0x0f) << 19; + + // Copy truncated exponent. + uint32_t exp = ((uint32_t)(*(inbuffer++)) & 0xf0)>>4; + exp |= ((uint32_t)(*inbuffer) & 0x7f) << 4; + if (exp != 0) + { + *val |= ((exp) - 1023 + 127) << 23; + } + + // Copy negative sign. + *val |= ((uint32_t)(*(inbuffer++)) & 0x80) << 24; + + return 8; + } + +}; + +} // namespace ros + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/node_handle.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,541 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_NODE_HANDLE_H_ +#define ROS_NODE_HANDLE_H_ + +#include "std_msgs/Time.h" +#include "rosserial_msgs/TopicInfo.h" +#include "rosserial_msgs/Log.h" +#include "rosserial_msgs/RequestParam.h" + +#define SYNC_SECONDS 5 + +#define MODE_FIRST_FF 0 +/* + * The second sync byte is a protocol version. It's value is 0xff for the first + * version of the rosserial protocol (used up to hydro), 0xfe for the second version + * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable + * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy + * rosserial_arduino. It must be changed in both this file and in + * rosserial_python/src/rosserial_python/SerialClient.py + */ +#define MODE_PROTOCOL_VER 1 +#define PROTOCOL_VER1 0xff // through groovy +#define PROTOCOL_VER2 0xfe // in hydro +#define PROTOCOL_VER PROTOCOL_VER2 +#define MODE_SIZE_L 2 +#define MODE_SIZE_H 3 +#define MODE_SIZE_CHECKSUM 4 // checksum for msg size received from size L and H +#define MODE_TOPIC_L 5 // waiting for topic id +#define MODE_TOPIC_H 6 +#define MODE_MESSAGE 7 +#define MODE_MSG_CHECKSUM 8 // checksum for msg and topic id + + +#define MSG_TIMEOUT 20 //20 milliseconds to recieve all of message data + +#include "msg.h" + +namespace ros { + + class NodeHandleBase_{ + public: + virtual int publish(int id, const Msg* msg)=0; + virtual int spinOnce()=0; + virtual bool connected()=0; + }; +} + +#include "publisher.h" +#include "subscriber.h" +#include "service_server.h" +#include "service_client.h" + +namespace ros { + + using rosserial_msgs::TopicInfo; + + /* Node Handle */ + template<class Hardware, + int MAX_SUBSCRIBERS=25, + int MAX_PUBLISHERS=25, + int INPUT_SIZE=512, + int OUTPUT_SIZE=512> + class NodeHandle_ : public NodeHandleBase_ + { + protected: + Hardware hardware_; + + /* time used for syncing */ + unsigned long rt_time; + + /* used for computing current time */ + unsigned long sec_offset, nsec_offset; + + unsigned char message_in[INPUT_SIZE]; + unsigned char message_out[OUTPUT_SIZE]; + + Publisher * publishers[MAX_PUBLISHERS]; + Subscriber_ * subscribers[MAX_SUBSCRIBERS]; + + /* + * Setup Functions + */ + public: + NodeHandle_() : configured_(false) { + + for(unsigned int i=0; i< MAX_PUBLISHERS; i++) + publishers[i] = 0; + + for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++) + subscribers[i] = 0; + + for(unsigned int i=0; i< INPUT_SIZE; i++) + message_in[i] = 0; + + for(unsigned int i=0; i< OUTPUT_SIZE; i++) + message_out[i] = 0; + + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + req_param_resp.floats_length = 0; + req_param_resp.floats = NULL; + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + } + + Hardware* getHardware(){ + return &hardware_; + } + + /* Start serial, initialize buffers */ + void initNode(){ + hardware_.init(); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + /* Start a named port, which may be network server IP, initialize buffers */ + void initNode(char *portName){ + hardware_.init(portName); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + protected: + //State machine variables for spinOnce + int mode_; + int bytes_; + int topic_; + int index_; + int checksum_; + + bool configured_; + + /* used for syncing the time */ + unsigned long last_sync_time; + unsigned long last_sync_receive_time; + unsigned long last_msg_timeout_time; + + public: + /* This function goes in your loop() function, it handles + * serial input and callbacks for subscribers. + */ + + + virtual int spinOnce(){ + + /* restart if timed out */ + unsigned long c_time = hardware_.time(); + if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){ + configured_ = false; + } + + /* reset if message has timed out */ + if ( mode_ != MODE_FIRST_FF){ + if (c_time > last_msg_timeout_time){ + mode_ = MODE_FIRST_FF; + } + } + + /* while available buffer, read data */ + while( true ) + { + int data = hardware_.read(); + if( data < 0 ) + break; + checksum_ += data; + if( mode_ == MODE_MESSAGE ){ /* message data being recieved */ + message_in[index_++] = data; + bytes_--; + if(bytes_ == 0) /* is message complete? if so, checksum */ + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_FIRST_FF ){ + if(data == 0xff){ + mode_++; + last_msg_timeout_time = c_time + MSG_TIMEOUT; + } + else if( hardware_.time() - c_time > (SYNC_SECONDS)){ + /* We have been stuck in spinOnce too long, return error */ + configured_=false; + return -2; + } + }else if( mode_ == MODE_PROTOCOL_VER ){ + if(data == PROTOCOL_VER){ + mode_++; + }else{ + mode_ = MODE_FIRST_FF; + if (configured_ == false) + requestSyncTime(); /* send a msg back showing our protocol version */ + } + }else if( mode_ == MODE_SIZE_L ){ /* bottom half of message size */ + bytes_ = data; + index_ = 0; + mode_++; + checksum_ = data; /* first byte for calculating size checksum */ + }else if( mode_ == MODE_SIZE_H ){ /* top half of message size */ + bytes_ += data<<8; + mode_++; + }else if( mode_ == MODE_SIZE_CHECKSUM ){ + if( (checksum_%256) == 255) + mode_++; + else + mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */ + }else if( mode_ == MODE_TOPIC_L ){ /* bottom half of topic id */ + topic_ = data; + mode_++; + checksum_ = data; /* first byte included in checksum */ + }else if( mode_ == MODE_TOPIC_H ){ /* top half of topic id */ + topic_ += data<<8; + mode_ = MODE_MESSAGE; + if(bytes_ == 0) + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */ + mode_ = MODE_FIRST_FF; + if( (checksum_%256) == 255){ + if(topic_ == TopicInfo::ID_PUBLISHER){ + requestSyncTime(); + negotiateTopics(); + last_sync_time = c_time; + last_sync_receive_time = c_time; + return -1; + }else if(topic_ == TopicInfo::ID_TIME){ + syncTime(message_in); + }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){ + req_param_resp.deserialize(message_in); + param_recieved= true; + }else if(topic_ == TopicInfo::ID_TX_STOP){ + configured_ = false; + }else{ + if(subscribers[topic_-100]) + subscribers[topic_-100]->callback( message_in ); + } + } + } + } + + /* occasionally sync time */ + if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){ + requestSyncTime(); + last_sync_time = c_time; + } + + return 0; + } + + + /* Are we connected to the PC? */ + virtual bool connected() { + return configured_; + }; + + /******************************************************************** + * Time functions + */ + + void requestSyncTime() + { + std_msgs::Time t; + publish(TopicInfo::ID_TIME, &t); + rt_time = hardware_.time(); + } + + void syncTime( unsigned char * data ) + { + std_msgs::Time t; + unsigned long offset = hardware_.time() - rt_time; + + t.deserialize(data); + t.data.sec += offset/1000; + t.data.nsec += (offset%1000)*1000000UL; + + this->setNow(t.data); + last_sync_receive_time = hardware_.time(); + } + + Time now(){ + unsigned long ms = hardware_.time(); + Time current_time; + current_time.sec = ms/1000 + sec_offset; + current_time.nsec = (ms%1000)*1000000UL + nsec_offset; + normalizeSecNSec(current_time.sec, current_time.nsec); + return current_time; + } + + void setNow( Time & new_now ) + { + unsigned long ms = hardware_.time(); + sec_offset = new_now.sec - ms/1000 - 1; + nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL; + normalizeSecNSec(sec_offset, nsec_offset); + } + + /******************************************************************** + * Topic Management + */ + + /* Register a new publisher */ + bool advertise(Publisher & p) + { + for(int i = 0; i < MAX_PUBLISHERS; i++){ + if(publishers[i] == 0){ // empty slot + publishers[i] = &p; + p.id_ = i+100+MAX_SUBSCRIBERS; + p.nh_ = this; + return true; + } + } + return false; + } + + /* Register a new subscriber */ + template<typename MsgT> + bool subscribe(Subscriber< MsgT> & s){ + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &s; + s.id_ = i+100; + return true; + } + } + return false; + } + + /* Register a new Service Server */ + template<typename MReq, typename MRes> + bool advertiseService(ServiceServer<MReq,MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &srv; + srv.id_ = i+100; + return v; + } + } + return false; + } + + /* Register a new Service Client */ + template<typename MReq, typename MRes> + bool serviceClient(ServiceClient<MReq, MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &srv; + srv.id_ = i+100; + return v; + } + } + return false; + } + + void negotiateTopics() + { + rosserial_msgs::TopicInfo ti; + int i; + for(i = 0; i < MAX_PUBLISHERS; i++) + { + if(publishers[i] != 0) // non-empty slot + { + ti.topic_id = publishers[i]->id_; + ti.topic_name = (char *) publishers[i]->topic_; + ti.message_type = (char *) publishers[i]->msg_->getType(); + ti.md5sum = (char *) publishers[i]->msg_->getMD5(); + ti.buffer_size = OUTPUT_SIZE; + publish( publishers[i]->getEndpointType(), &ti ); + } + } + for(i = 0; i < MAX_SUBSCRIBERS; i++) + { + if(subscribers[i] != 0) // non-empty slot + { + ti.topic_id = subscribers[i]->id_; + ti.topic_name = (char *) subscribers[i]->topic_; + ti.message_type = (char *) subscribers[i]->getMsgType(); + ti.md5sum = (char *) subscribers[i]->getMsgMD5(); + ti.buffer_size = INPUT_SIZE; + publish( subscribers[i]->getEndpointType(), &ti ); + } + } + configured_ = true; + } + + virtual int publish(int id, const Msg * msg) + { + if(id >= 100 && !configured_) + return 0; + + /* serialize message */ + unsigned int l = msg->serialize(message_out+7); + + /* setup the header */ + message_out[0] = 0xff; + message_out[1] = PROTOCOL_VER; + message_out[2] = (unsigned char) ((unsigned int)l&255); + message_out[3] = (unsigned char) ((unsigned int)l>>8); + message_out[4] = 255 - ((message_out[2] + message_out[3])%256); + message_out[5] = (unsigned char) ((int)id&255); + message_out[6] = (unsigned char) ((int)id>>8); + + /* calculate checksum */ + int chk = 0; + for(int i =5; i<l+7; i++) + chk += message_out[i]; + l += 7; + message_out[l++] = 255 - (chk%256); + + if( l <= OUTPUT_SIZE ){ + hardware_.write(message_out, l); + return l; + }else{ + logerror("Message from device dropped: message larger than buffer."); + return -1; + } + } + + /******************************************************************** + * Logging + */ + + private: + void log(char byte, const char * msg){ + rosserial_msgs::Log l; + l.level= byte; + l.msg = (char*)msg; + publish(rosserial_msgs::TopicInfo::ID_LOG, &l); + } + + public: + void logdebug(const char* msg){ + log(rosserial_msgs::Log::ROSDEBUG, msg); + } + void loginfo(const char * msg){ + log(rosserial_msgs::Log::INFO, msg); + } + void logwarn(const char *msg){ + log(rosserial_msgs::Log::WARN, msg); + } + void logerror(const char*msg){ + log(rosserial_msgs::Log::ERROR, msg); + } + void logfatal(const char*msg){ + log(rosserial_msgs::Log::FATAL, msg); + } + + /******************************************************************** + * Parameters + */ + + private: + bool param_recieved; + rosserial_msgs::RequestParamResponse req_param_resp; + + bool requestParam(const char * name, int time_out = 1000){ + param_recieved = false; + rosserial_msgs::RequestParamRequest req; + req.name = (char*)name; + publish(TopicInfo::ID_PARAMETER_REQUEST, &req); + unsigned int end_time = hardware_.time() + time_out; + while(!param_recieved ){ + spinOnce(); + if (hardware_.time() > end_time) return false; + } + return true; + } + + public: + bool getParam(const char* name, int* param, int length =1){ + if (requestParam(name) ){ + if (length == req_param_resp.ints_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.ints[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, float* param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.floats_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.floats[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, char** param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.strings_length){ + //copy it over + for(int i=0; i<length; i++) + strcpy(param[i],req_param_resp.strings[i]); + return true; + } + } + return false; + } + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/publisher.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_PUBLISHER_H_ +#define _ROS_PUBLISHER_H_ + +#include "rosserial_msgs/TopicInfo.h" +#include "node_handle.h" + +namespace ros { + + /* Generic Publisher */ + class Publisher + { + public: + Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) : + topic_(topic_name), + msg_(msg), + endpoint_(endpoint) {}; + + int publish( const Msg * msg ) { return nh_->publish(id_, msg); }; + int getEndpointType(){ return endpoint_; } + + const char * topic_; + Msg *msg_; + // id_ and no_ are set by NodeHandle when we advertise + int id_; + NodeHandleBase_* nh_; + + private: + int endpoint_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_client.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_CLIENT_H_ +#define _ROS_SERVICE_CLIENT_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "publisher.h" +#include "subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceClient : public Subscriber_ { + public: + ServiceClient(const char* topic_name) : + pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->waiting = true; + } + + virtual void call(const MReq & request, MRes & response) + { + if(!pub.nh_->connected()) return; + ret = &response; + waiting = true; + pub.publish(&request); + while(waiting && pub.nh_->connected()) + if(pub.nh_->spinOnce() < 0) break; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + ret->deserialize(data); + waiting = false; + } + virtual const char * getMsgType(){ return this->resp.getType(); } + virtual const char * getMsgMD5(){ return this->resp.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + MRes * ret; + bool waiting; + Publisher pub; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_server.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_SERVER_H_ +#define _ROS_SERVICE_SERVER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "publisher.h" +#include "subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceServer : public Subscriber_ { + public: + typedef void(*CallbackT)(const MReq&, MRes&); + + ServiceServer(const char* topic_name, CallbackT cb) : + pub(topic_name, &resp, rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->cb_ = cb; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + req.deserialize(data); + cb_(req,resp); + pub.publish(&resp); + } + virtual const char * getMsgType(){ return this->req.getType(); } + virtual const char * getMsgMD5(){ return this->req.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + Publisher pub; + private: + CallbackT cb_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/subscriber.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_SUBSCRIBER_H_ +#define ROS_SUBSCRIBER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +namespace ros { + + /* Base class for objects subscribers. */ + class Subscriber_ + { + public: + virtual void callback(unsigned char *data)=0; + virtual int getEndpointType()=0; + + // id_ is set by NodeHandle when we advertise + int id_; + + virtual const char * getMsgType()=0; + virtual const char * getMsgMD5()=0; + const char * topic_; + }; + + + /* Actual subscriber, templated on message type. */ + template<typename MsgT> + class Subscriber: public Subscriber_{ + public: + typedef void(*CallbackT)(const MsgT&); + MsgT msg; + + Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) : + cb_(cb), + endpoint_(endpoint) + { + topic_ = topic_name; + }; + + virtual void callback(unsigned char* data){ + msg.deserialize(data); + this->cb_(msg); + } + + virtual const char * getMsgType(){ return this->msg.getType(); } + virtual const char * getMsgMD5(){ return this->msg.getMD5(); } + virtual int getEndpointType(){ return endpoint_; } + + private: + CallbackT cb_; + int endpoint_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/time.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,72 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TIME_H_ +#define ROS_TIME_H_ + +#include <ros/duration.h> +#include <math.h> + +namespace ros +{ + void normalizeSecNSec(unsigned long &sec, unsigned long &nsec); + + class Time + { + public: + unsigned long sec, nsec; + + Time() : sec(0), nsec(0) {} + Time(unsigned long _sec, unsigned long _nsec) : sec(_sec), nsec(_nsec) + { + normalizeSecNSec(sec, nsec); + } + + double toSec() const { return (double)sec + 1e-9*(double)nsec; }; + void fromSec(double t) { sec = (unsigned long) floor(t); nsec = (unsigned long) floor((t-sec) * 1e9); }; + + unsigned long toNsec() { return (unsigned long)sec*1000000000ull + (unsigned long)nsec; }; + Time& fromNSec(long t); + + Time& operator +=(const Duration &rhs); + Time& operator -=(const Duration &rhs); + + static Time now(); + static void setNow( Time & new_now); + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Empty.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_SERVICE_Empty_h +#define _ROS_SERVICE_Empty_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char EMPTY[] = "roscpp/Empty"; + + class EmptyRequest : public ros::Msg + { + public: + + EmptyRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class EmptyResponse : public ros::Msg + { + public: + + EmptyResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class Empty { + public: + typedef EmptyRequest Request; + typedef EmptyResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/GetLoggers.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_GetLoggers_h +#define _ROS_SERVICE_GetLoggers_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "roscpp/Logger.h" + +namespace roscpp +{ + +static const char GETLOGGERS[] = "roscpp/GetLoggers"; + + class GetLoggersRequest : public ros::Msg + { + public: + + GetLoggersRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetLoggersResponse : public ros::Msg + { + public: + uint8_t loggers_length; + roscpp::Logger st_loggers; + roscpp::Logger * loggers; + + GetLoggersResponse(): + loggers_length(0), loggers(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = loggers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->loggers[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t loggers_lengthT = *(inbuffer + offset++); + if(loggers_lengthT > loggers_length) + this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger)); + offset += 3; + loggers_length = loggers_lengthT; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->st_loggers.deserialize(inbuffer + offset); + memcpy( &(this->loggers[i]), &(this->st_loggers), sizeof(roscpp::Logger)); + } + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "32e97e85527d4678a8f9279894bb64b0"; }; + + }; + + class GetLoggers { + public: + typedef GetLoggersRequest Request; + typedef GetLoggersResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Logger.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_roscpp_Logger_h +#define _ROS_roscpp_Logger_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + + class Logger : public ros::Msg + { + public: + const char* name; + const char* level; + + Logger(): + name(""), + level("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_level = strlen(this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return "roscpp/Logger"; }; + const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/SetLoggerLevel.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_SERVICE_SetLoggerLevel_h +#define _ROS_SERVICE_SetLoggerLevel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char SETLOGGERLEVEL[] = "roscpp/SetLoggerLevel"; + + class SetLoggerLevelRequest : public ros::Msg + { + public: + const char* logger; + const char* level; + + SetLoggerLevelRequest(): + logger(""), + level("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_logger = strlen(this->logger); + memcpy(outbuffer + offset, &length_logger, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->logger, length_logger); + offset += length_logger; + uint32_t length_level = strlen(this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_logger; + memcpy(&length_logger, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_logger; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_logger-1]=0; + this->logger = (char *)(inbuffer + offset-1); + offset += length_logger; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "51da076440d78ca1684d36c868df61ea"; }; + + }; + + class SetLoggerLevelResponse : public ros::Msg + { + public: + + SetLoggerLevelResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetLoggerLevel { + public: + typedef SetLoggerLevelRequest Request; + typedef SetLoggerLevelResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp_tutorials/TwoInts.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,164 @@ +#ifndef _ROS_SERVICE_TwoInts_h +#define _ROS_SERVICE_TwoInts_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp_tutorials +{ + +static const char TWOINTS[] = "roscpp_tutorials/TwoInts"; + + class TwoIntsRequest : public ros::Msg + { + public: + int64_t a; + int64_t b; + + TwoIntsRequest(): + a(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->b); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->a = u_a.real; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->b = u_b.real; + offset += sizeof(this->b); + return offset; + } + + const char * getType(){ return TWOINTS; }; + const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; }; + + }; + + class TwoIntsResponse : public ros::Msg + { + public: + int64_t sum; + + TwoIntsResponse(): + sum(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.real = this->sum; + *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->sum); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.base = 0; + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->sum = u_sum.real; + offset += sizeof(this->sum); + return offset; + } + + const char * getType(){ return TWOINTS; }; + const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; }; + + }; + + class TwoInts { + public: + typedef TwoIntsRequest Request; + typedef TwoIntsResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosgraph_msgs/Clock.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_rosgraph_msgs_Clock_h +#define _ROS_rosgraph_msgs_Clock_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace rosgraph_msgs +{ + + class Clock : public ros::Msg + { + public: + ros::Time clock; + + Clock(): + clock() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->clock.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->clock.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->clock.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->clock.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->clock.sec); + *(outbuffer + offset + 0) = (this->clock.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->clock.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->clock.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->clock.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->clock.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->clock.sec = ((uint32_t) (*(inbuffer + offset))); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->clock.sec); + this->clock.nsec = ((uint32_t) (*(inbuffer + offset))); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->clock.nsec); + return offset; + } + + const char * getType(){ return "rosgraph_msgs/Clock"; }; + const char * getMD5(){ return "a9c97c1d230cfc112e270351a944ee47"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosgraph_msgs/Log.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,173 @@ +#ifndef _ROS_rosgraph_msgs_Log_h +#define _ROS_rosgraph_msgs_Log_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace rosgraph_msgs +{ + + class Log : public ros::Msg + { + public: + std_msgs::Header header; + int8_t level; + const char* name; + const char* msg; + const char* file; + const char* function; + uint32_t line; + uint8_t topics_length; + char* st_topics; + char* * topics; + enum { DEBUG = 1 }; + enum { INFO = 2 }; + enum { WARN = 4 }; + enum { ERROR = 8 }; + enum { FATAL = 16 }; + + Log(): + header(), + level(0), + name(""), + msg(""), + file(""), + function(""), + line(0), + topics_length(0), topics(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + int8_t real; + uint8_t base; + } u_level; + u_level.real = this->level; + *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_msg = strlen(this->msg); + memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->msg, length_msg); + offset += length_msg; + uint32_t length_file = strlen(this->file); + memcpy(outbuffer + offset, &length_file, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->file, length_file); + offset += length_file; + uint32_t length_function = strlen(this->function); + memcpy(outbuffer + offset, &length_function, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->function, length_function); + offset += length_function; + *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF; + offset += sizeof(this->line); + *(outbuffer + offset++) = topics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_topicsi = strlen(this->topics[i]); + memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topics[i], length_topicsi); + offset += length_topicsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + int8_t real; + uint8_t base; + } u_level; + u_level.base = 0; + u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->level = u_level.real; + offset += sizeof(this->level); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_msg; + memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_msg; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_msg-1]=0; + this->msg = (char *)(inbuffer + offset-1); + offset += length_msg; + uint32_t length_file; + memcpy(&length_file, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_file; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_file-1]=0; + this->file = (char *)(inbuffer + offset-1); + offset += length_file; + uint32_t length_function; + memcpy(&length_function, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_function; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_function-1]=0; + this->function = (char *)(inbuffer + offset-1); + offset += length_function; + this->line = ((uint32_t) (*(inbuffer + offset))); + this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->line); + uint8_t topics_lengthT = *(inbuffer + offset++); + if(topics_lengthT > topics_length) + this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); + offset += 3; + topics_length = topics_lengthT; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_st_topics; + memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_topics; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_topics-1]=0; + this->st_topics = (char *)(inbuffer + offset-1); + offset += length_st_topics; + memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "rosgraph_msgs/Log"; }; + const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rospy_tutorials/AddTwoInts.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,164 @@ +#ifndef _ROS_SERVICE_AddTwoInts_h +#define _ROS_SERVICE_AddTwoInts_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rospy_tutorials +{ + +static const char ADDTWOINTS[] = "rospy_tutorials/AddTwoInts"; + + class AddTwoIntsRequest : public ros::Msg + { + public: + int64_t a; + int64_t b; + + AddTwoIntsRequest(): + a(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->b); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->a = u_a.real; + offset += sizeof(this->a); + union { + int64_t real; + uint64_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->b = u_b.real; + offset += sizeof(this->b); + return offset; + } + + const char * getType(){ return ADDTWOINTS; }; + const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; }; + + }; + + class AddTwoIntsResponse : public ros::Msg + { + public: + int64_t sum; + + AddTwoIntsResponse(): + sum(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.real = this->sum; + *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->sum); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_sum; + u_sum.base = 0; + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->sum = u_sum.real; + offset += sizeof(this->sum); + return offset; + } + + const char * getType(){ return ADDTWOINTS; }; + const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; }; + + }; + + class AddTwoInts { + public: + typedef AddTwoIntsRequest Request; + typedef AddTwoIntsResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rospy_tutorials/BadTwoInts.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,148 @@ +#ifndef _ROS_SERVICE_BadTwoInts_h +#define _ROS_SERVICE_BadTwoInts_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rospy_tutorials +{ + +static const char BADTWOINTS[] = "rospy_tutorials/BadTwoInts"; + + class BadTwoIntsRequest : public ros::Msg + { + public: + int64_t a; + int32_t b; + + BadTwoIntsRequest(): + a(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->a); + union { + int32_t real; + uint32_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->a = u_a.real; + offset += sizeof(this->a); + union { + int32_t real; + uint32_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b = u_b.real; + offset += sizeof(this->b); + return offset; + } + + const char * getType(){ return BADTWOINTS; }; + const char * getMD5(){ return "29bb5c7dea8bf822f53e94b0ee5a3a56"; }; + + }; + + class BadTwoIntsResponse : public ros::Msg + { + public: + int32_t sum; + + BadTwoIntsResponse(): + sum(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_sum; + u_sum.real = this->sum; + *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sum); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_sum; + u_sum.base = 0; + u_sum.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_sum.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_sum.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_sum.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->sum = u_sum.real; + offset += sizeof(this->sum); + return offset; + } + + const char * getType(){ return BADTWOINTS; }; + const char * getMD5(){ return "0ba699c25c9418c0366f3595c0c8e8ec"; }; + + }; + + class BadTwoInts { + public: + typedef BadTwoIntsRequest Request; + typedef BadTwoIntsResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rospy_tutorials/Floats.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,77 @@ +#ifndef _ROS_rospy_tutorials_Floats_h +#define _ROS_rospy_tutorials_Floats_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rospy_tutorials +{ + + class Floats : public ros::Msg + { + public: + uint8_t data_length; + float st_data; + float * data; + + Floats(): + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "rospy_tutorials/Floats"; }; + const char * getMD5(){ return "420cd38b6b071cd49f2970c3e2cee511"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rospy_tutorials/HeaderString.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_rospy_tutorials_HeaderString_h +#define _ROS_rospy_tutorials_HeaderString_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace rospy_tutorials +{ + + class HeaderString : public ros::Msg + { + public: + std_msgs::Header header; + const char* data; + + HeaderString(): + header(), + data("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_data = strlen(this->data); + memcpy(outbuffer + offset, &length_data, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->data, length_data); + offset += length_data; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_data; + memcpy(&length_data, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_data-1]=0; + this->data = (char *)(inbuffer + offset-1); + offset += length_data; + return offset; + } + + const char * getType(){ return "rospy_tutorials/HeaderString"; }; + const char * getMD5(){ return "c99a9440709e4d4a9716d55b8270d5e7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/Log.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_rosserial_msgs_Log_h +#define _ROS_rosserial_msgs_Log_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class Log : public ros::Msg + { + public: + uint8_t level; + const char* msg; + enum { ROSDEBUG = 0 }; + enum { INFO = 1 }; + enum { WARN = 2 }; + enum { ERROR = 3 }; + enum { FATAL = 4 }; + + Log(): + level(0), + msg("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_msg = strlen(this->msg); + memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->msg, length_msg); + offset += length_msg; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->level = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->level); + uint32_t length_msg; + memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_msg; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_msg-1]=0; + this->msg = (char *)(inbuffer + offset-1); + offset += length_msg; + return offset; + } + + const char * getType(){ return "rosserial_msgs/Log"; }; + const char * getMD5(){ return "11abd731c25933261cd6183bd12d6295"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestMessageInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,119 @@ +#ifndef _ROS_SERVICE_RequestMessageInfo_h +#define _ROS_SERVICE_RequestMessageInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTMESSAGEINFO[] = "rosserial_msgs/RequestMessageInfo"; + + class RequestMessageInfoRequest : public ros::Msg + { + public: + const char* type; + + RequestMessageInfoRequest(): + type("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_type = strlen(this->type); + memcpy(outbuffer + offset, &length_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->type, length_type); + offset += length_type; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_type; + memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_type-1]=0; + this->type = (char *)(inbuffer + offset-1); + offset += length_type; + return offset; + } + + const char * getType(){ return REQUESTMESSAGEINFO; }; + const char * getMD5(){ return "dc67331de85cf97091b7d45e5c64ab75"; }; + + }; + + class RequestMessageInfoResponse : public ros::Msg + { + public: + const char* md5; + const char* definition; + + RequestMessageInfoResponse(): + md5(""), + definition("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_md5 = strlen(this->md5); + memcpy(outbuffer + offset, &length_md5, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->md5, length_md5); + offset += length_md5; + uint32_t length_definition = strlen(this->definition); + memcpy(outbuffer + offset, &length_definition, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->definition, length_definition); + offset += length_definition; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_md5; + memcpy(&length_md5, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_md5-1]=0; + this->md5 = (char *)(inbuffer + offset-1); + offset += length_md5; + uint32_t length_definition; + memcpy(&length_definition, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_definition; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_definition-1]=0; + this->definition = (char *)(inbuffer + offset-1); + offset += length_definition; + return offset; + } + + const char * getType(){ return REQUESTMESSAGEINFO; }; + const char * getMD5(){ return "fe452186a069bed40f09b8628fe5eac8"; }; + + }; + + class RequestMessageInfo { + public: + typedef RequestMessageInfoRequest Request; + typedef RequestMessageInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestParam.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,197 @@ +#ifndef _ROS_SERVICE_RequestParam_h +#define _ROS_SERVICE_RequestParam_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam"; + + class RequestParamRequest : public ros::Msg + { + public: + const char* name; + + RequestParamRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class RequestParamResponse : public ros::Msg + { + public: + uint8_t ints_length; + int32_t st_ints; + int32_t * ints; + uint8_t floats_length; + float st_floats; + float * floats; + uint8_t strings_length; + char* st_strings; + char* * strings; + + RequestParamResponse(): + ints_length(0), ints(NULL), + floats_length(0), floats(NULL), + strings_length(0), strings(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = ints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_intsi; + u_intsi.real = this->ints[i]; + *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ints[i]); + } + *(outbuffer + offset++) = floats_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_floatsi; + u_floatsi.real = this->floats[i]; + *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->floats[i]); + } + *(outbuffer + offset++) = strings_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < strings_length; i++){ + uint32_t length_stringsi = strlen(this->strings[i]); + memcpy(outbuffer + offset, &length_stringsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->strings[i], length_stringsi); + offset += length_stringsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t ints_lengthT = *(inbuffer + offset++); + if(ints_lengthT > ints_length) + this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t)); + offset += 3; + ints_length = ints_lengthT; + for( uint8_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_ints; + u_st_ints.base = 0; + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ints = u_st_ints.real; + offset += sizeof(this->st_ints); + memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t)); + } + uint8_t floats_lengthT = *(inbuffer + offset++); + if(floats_lengthT > floats_length) + this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float)); + offset += 3; + floats_length = floats_lengthT; + for( uint8_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_st_floats; + u_st_floats.base = 0; + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_floats = u_st_floats.real; + offset += sizeof(this->st_floats); + memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float)); + } + uint8_t strings_lengthT = *(inbuffer + offset++); + if(strings_lengthT > strings_length) + this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*)); + offset += 3; + strings_length = strings_lengthT; + for( uint8_t i = 0; i < strings_length; i++){ + uint32_t length_st_strings; + memcpy(&length_st_strings, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_strings; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_strings-1]=0; + this->st_strings = (char *)(inbuffer + offset-1); + offset += length_st_strings; + memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; }; + + }; + + class RequestParam { + public: + typedef RequestParamRequest Request; + typedef RequestParamResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestServiceInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,135 @@ +#ifndef _ROS_SERVICE_RequestServiceInfo_h +#define _ROS_SERVICE_RequestServiceInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTSERVICEINFO[] = "rosserial_msgs/RequestServiceInfo"; + + class RequestServiceInfoRequest : public ros::Msg + { + public: + const char* service; + + RequestServiceInfoRequest(): + service("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_service = strlen(this->service); + memcpy(outbuffer + offset, &length_service, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->service, length_service); + offset += length_service; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_service; + memcpy(&length_service, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_service; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_service-1]=0; + this->service = (char *)(inbuffer + offset-1); + offset += length_service; + return offset; + } + + const char * getType(){ return REQUESTSERVICEINFO; }; + const char * getMD5(){ return "1cbcfa13b08f6d36710b9af8741e6112"; }; + + }; + + class RequestServiceInfoResponse : public ros::Msg + { + public: + const char* service_md5; + const char* request_md5; + const char* response_md5; + + RequestServiceInfoResponse(): + service_md5(""), + request_md5(""), + response_md5("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_service_md5 = strlen(this->service_md5); + memcpy(outbuffer + offset, &length_service_md5, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->service_md5, length_service_md5); + offset += length_service_md5; + uint32_t length_request_md5 = strlen(this->request_md5); + memcpy(outbuffer + offset, &length_request_md5, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->request_md5, length_request_md5); + offset += length_request_md5; + uint32_t length_response_md5 = strlen(this->response_md5); + memcpy(outbuffer + offset, &length_response_md5, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->response_md5, length_response_md5); + offset += length_response_md5; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_service_md5; + memcpy(&length_service_md5, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_service_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_service_md5-1]=0; + this->service_md5 = (char *)(inbuffer + offset-1); + offset += length_service_md5; + uint32_t length_request_md5; + memcpy(&length_request_md5, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_request_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_request_md5-1]=0; + this->request_md5 = (char *)(inbuffer + offset-1); + offset += length_request_md5; + uint32_t length_response_md5; + memcpy(&length_response_md5, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_response_md5; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_response_md5-1]=0; + this->response_md5 = (char *)(inbuffer + offset-1); + offset += length_response_md5; + return offset; + } + + const char * getType(){ return REQUESTSERVICEINFO; }; + const char * getMD5(){ return "c3d6dd25b909596479fbbc6559fa6874"; }; + + }; + + class RequestServiceInfo { + public: + typedef RequestServiceInfoRequest Request; + typedef RequestServiceInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/TopicInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,125 @@ +#ifndef _ROS_rosserial_msgs_TopicInfo_h +#define _ROS_rosserial_msgs_TopicInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class TopicInfo : public ros::Msg + { + public: + uint16_t topic_id; + const char* topic_name; + const char* message_type; + const char* md5sum; + int32_t buffer_size; + enum { ID_PUBLISHER = 0 }; + enum { ID_SUBSCRIBER = 1 }; + enum { ID_SERVICE_SERVER = 2 }; + enum { ID_SERVICE_CLIENT = 4 }; + enum { ID_PARAMETER_REQUEST = 6 }; + enum { ID_LOG = 7 }; + enum { ID_TIME = 10 }; + enum { ID_TX_STOP = 11 }; + + TopicInfo(): + topic_id(0), + topic_name(""), + message_type(""), + md5sum(""), + buffer_size(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF; + offset += sizeof(this->topic_id); + uint32_t length_topic_name = strlen(this->topic_name); + memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic_name, length_topic_name); + offset += length_topic_name; + uint32_t length_message_type = strlen(this->message_type); + memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->message_type, length_message_type); + offset += length_message_type; + uint32_t length_md5sum = strlen(this->md5sum); + memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->md5sum, length_md5sum); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.real = this->buffer_size; + *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->buffer_size); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->topic_id = ((uint16_t) (*(inbuffer + offset))); + this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->topic_id); + uint32_t length_topic_name; + memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic_name-1]=0; + this->topic_name = (char *)(inbuffer + offset-1); + offset += length_topic_name; + uint32_t length_message_type; + memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message_type-1]=0; + this->message_type = (char *)(inbuffer + offset-1); + offset += length_message_type; + uint32_t length_md5sum; + memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_md5sum; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_md5sum-1]=0; + this->md5sum = (char *)(inbuffer + offset-1); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.base = 0; + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->buffer_size = u_buffer_size.real; + offset += sizeof(this->buffer_size); + return offset; + } + + const char * getType(){ return "rosserial_msgs/TopicInfo"; }; + const char * getMD5(){ return "0ad51f88fc44892f8c10684077646005"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CameraInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,37 @@ +#ifndef _ROS_sensor_msgs_CameraInfo_h +#define _ROS_sensor_msgs_CameraInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/RegionOfInterest.h" + +namespace sensor_msgs +{ + + class CameraInfo : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + const char* distortion_model; + uint8_t D_length; + float st_D; + float * D; + float K[9]; + float R[9]; + float P[12]; + uint32_t binning_x; + uint32_t binning_y; + sensor_msgs::RegionOfInterest roi; + + CameraInfo(): + header(), + height(0), + width(0), + distortion_model(""), + D_length(0), D(NULL), +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/ChannelFloat32.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,86 @@ + #ifndef _ROS_sensor_msgs_ChannelFloat32_h +#define _ROS_sensor_msgs_ChannelFloat32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class ChannelFloat32 : public ros::Msg + { + public: + char * name; + uint8_t values_length; + float st_values; + float * values; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t * length_name = (uint32_t *)(outbuffer + offset); + *length_name = strlen( (const char*) this->name); + offset += 4; + memcpy(outbuffer + offset, this->name, *length_name); + offset += *length_name; + *(outbuffer + offset++) = values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_valuesi; + u_valuesi.real = this->values[i]; + *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->values[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name = *(uint32_t *)(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; + uint8_t values_lengthT = *(inbuffer + offset++); + if(values_lengthT > values_length) + this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); + offset += 3; + values_length = values_lengthT; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_st_values; + u_st_values.base = 0; + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_values = u_st_values.real; + offset += sizeof(this->st_values); + memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/ChannelFloat32"; }; + virtual const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CompressedImage.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,73 @@ +#ifndef _ROS_sensor_msgs_CompressedImage_h +#define _ROS_sensor_msgs_CompressedImage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class CompressedImage : public ros::Msg + { + public: + std_msgs::Header header; + char * format; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t * length_format = (uint32_t *)(outbuffer + offset); + *length_format = strlen( (const char*) this->format); + offset += 4; + memcpy(outbuffer + offset, this->format, *length_format); + offset += *length_format; + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_format = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_format; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_format-1]=0; + this->format = (char *)(inbuffer + offset-1); + offset += length_format; + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/CompressedImage"; }; + virtual const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Image.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,111 @@ +#ifndef _ROS_sensor_msgs_Image_h +#define _ROS_sensor_msgs_Image_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Image : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + char * encoding; + uint8_t is_bigendian; + uint32_t step; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + uint32_t * length_encoding = (uint32_t *)(outbuffer + offset); + *length_encoding = strlen( (const char*) this->encoding); + offset += 4; + memcpy(outbuffer + offset, this->encoding, *length_encoding); + offset += *length_encoding; + *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; + offset += sizeof(this->step); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t length_encoding = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_encoding; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_encoding-1]=0; + this->encoding = (char *)(inbuffer + offset-1); + offset += length_encoding; + this->is_bigendian |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->is_bigendian); + this->step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->step); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/Image"; }; + virtual const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Imu.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,145 @@ +#ifndef _ROS_sensor_msgs_Imu_h +#define _ROS_sensor_msgs_Imu_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" +#include "geometry_msgs/Vector3.h" + +namespace sensor_msgs +{ + + class Imu : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Quaternion orientation; + float orientation_covariance[9]; + geometry_msgs::Vector3 angular_velocity; + float angular_velocity_covariance[9]; + geometry_msgs::Vector3 linear_acceleration; + float linear_acceleration_covariance[9]; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->orientation.serialize(outbuffer + offset); + unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]); + int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255); + if(exp_orientation_covariancei != 0) + exp_orientation_covariancei += 1023-127; + int32_t sig_orientation_covariancei = *val_orientation_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_orientation_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_orientation_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_orientation_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_orientation_covariancei<<4) & 0xF0) | ((sig_orientation_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_orientation_covariancei>>4) & 0x7F; + if(this->orientation_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + offset += this->angular_velocity.serialize(outbuffer + offset); + unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]); + int32_t exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255); + if(exp_angular_velocity_covariancei != 0) + exp_angular_velocity_covariancei += 1023-127; + int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_angular_velocity_covariancei<<4) & 0xF0) | ((sig_angular_velocity_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_angular_velocity_covariancei>>4) & 0x7F; + if(this->angular_velocity_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + offset += this->linear_acceleration.serialize(outbuffer + offset); + unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]); + int32_t exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255); + if(exp_linear_acceleration_covariancei != 0) + exp_linear_acceleration_covariancei += 1023-127; + int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_linear_acceleration_covariancei<<4) & 0xF0) | ((sig_linear_acceleration_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_linear_acceleration_covariancei>>4) & 0x7F; + if(this->linear_acceleration_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + uint8_t * orientation_covariance_val = (uint8_t*) this->orientation_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_orientation_covariancei = (uint32_t*) &(this->orientation_covariance[i]); + offset += 3; + *val_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_orientation_covariancei !=0) + *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i]; + } + offset += this->angular_velocity.deserialize(inbuffer + offset); + uint8_t * angular_velocity_covariance_val = (uint8_t*) this->angular_velocity_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_angular_velocity_covariancei = (uint32_t*) &(this->angular_velocity_covariance[i]); + offset += 3; + *val_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_angular_velocity_covariancei !=0) + *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i]; + } + offset += this->linear_acceleration.deserialize(inbuffer + offset); + uint8_t * linear_acceleration_covariance_val = (uint8_t*) this->linear_acceleration_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_linear_acceleration_covariancei = (uint32_t*) &(this->linear_acceleration_covariance[i]); + offset += 3; + *val_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_linear_acceleration_covariancei !=0) + *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i]; + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/Imu"; }; + virtual const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/JointState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,194 @@ +#ifndef _ROS_sensor_msgs_JointState_h +#define _ROS_sensor_msgs_JointState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class JointState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t name_length; + char* st_name; + char* * name; + uint8_t position_length; + float st_position; + float * position; + uint8_t velocity_length; + float st_velocity; + float * velocity; + uint8_t effort_length; + float st_effort; + float * effort; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t * length_namei = (uint32_t *)(outbuffer + offset); + *length_namei = strlen( (const char*) this->name[i]); + offset += 4; + memcpy(outbuffer + offset, this->name[i], *length_namei); + offset += *length_namei; + } + *(outbuffer + offset++) = position_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < position_length; i++){ + int32_t * val_positioni = (long *) &(this->position[i]); + int32_t exp_positioni = (((*val_positioni)>>23)&255); + if(exp_positioni != 0) + exp_positioni += 1023-127; + int32_t sig_positioni = *val_positioni; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_positioni<<5) & 0xff; + *(outbuffer + offset++) = (sig_positioni>>3) & 0xff; + *(outbuffer + offset++) = (sig_positioni>>11) & 0xff; + *(outbuffer + offset++) = ((exp_positioni<<4) & 0xF0) | ((sig_positioni>>19)&0x0F); + *(outbuffer + offset++) = (exp_positioni>>4) & 0x7F; + if(this->position[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset++) = velocity_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < velocity_length; i++){ + int32_t * val_velocityi = (long *) &(this->velocity[i]); + int32_t exp_velocityi = (((*val_velocityi)>>23)&255); + if(exp_velocityi != 0) + exp_velocityi += 1023-127; + int32_t sig_velocityi = *val_velocityi; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_velocityi<<5) & 0xff; + *(outbuffer + offset++) = (sig_velocityi>>3) & 0xff; + *(outbuffer + offset++) = (sig_velocityi>>11) & 0xff; + *(outbuffer + offset++) = ((exp_velocityi<<4) & 0xF0) | ((sig_velocityi>>19)&0x0F); + *(outbuffer + offset++) = (exp_velocityi>>4) & 0x7F; + if(this->velocity[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset++) = effort_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < effort_length; i++){ + int32_t * val_efforti = (long *) &(this->effort[i]); + int32_t exp_efforti = (((*val_efforti)>>23)&255); + if(exp_efforti != 0) + exp_efforti += 1023-127; + int32_t sig_efforti = *val_efforti; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_efforti<<5) & 0xff; + *(outbuffer + offset++) = (sig_efforti>>3) & 0xff; + *(outbuffer + offset++) = (sig_efforti>>11) & 0xff; + *(outbuffer + offset++) = ((exp_efforti<<4) & 0xF0) | ((sig_efforti>>19)&0x0F); + *(outbuffer + offset++) = (exp_efforti>>4) & 0x7F; + if(this->effort[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name = *(uint32_t *)(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*)); + } + uint8_t position_lengthT = *(inbuffer + offset++); + if(position_lengthT > position_length) + this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); + offset += 3; + position_length = position_lengthT; + for( uint8_t i = 0; i < position_length; i++){ + uint32_t * val_st_position = (uint32_t*) &(this->st_position); + offset += 3; + *val_st_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_position !=0) + *val_st_position |= ((exp_st_position)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_position = -this->st_position; + memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); + } + uint8_t velocity_lengthT = *(inbuffer + offset++); + if(velocity_lengthT > velocity_length) + this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float)); + offset += 3; + velocity_length = velocity_lengthT; + for( uint8_t i = 0; i < velocity_length; i++){ + uint32_t * val_st_velocity = (uint32_t*) &(this->st_velocity); + offset += 3; + *val_st_velocity = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_velocity = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_velocity !=0) + *val_st_velocity |= ((exp_st_velocity)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_velocity = -this->st_velocity; + memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float)); + } + uint8_t effort_lengthT = *(inbuffer + offset++); + if(effort_lengthT > effort_length) + this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float)); + offset += 3; + effort_length = effort_lengthT; + for( uint8_t i = 0; i < effort_length; i++){ + uint32_t * val_st_effort = (uint32_t*) &(this->st_effort); + offset += 3; + *val_st_effort = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_effort = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_effort !=0) + *val_st_effort |= ((exp_st_effort)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_effort = -this->st_effort; + memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float)); + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/JointState"; }; + virtual const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/LaserScan.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,268 @@ +#ifndef _ROS_sensor_msgs_LaserScan_h +#define _ROS_sensor_msgs_LaserScan_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class LaserScan : public ros::Msg + { + public: + std_msgs::Header header; + float angle_min; + float angle_max; + float angle_increment; + float time_increment; + float scan_time; + float range_min; + float range_max; + uint8_t ranges_length; + float st_ranges; + float * ranges; + uint8_t intensities_length; + float st_intensities; + float * intensities; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.real = this->angle_min; + *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.real = this->angle_max; + *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.real = this->angle_increment; + *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.real = this->time_increment; + *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.real = this->scan_time; + *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.real = this->range_min; + *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.real = this->range_max; + *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_max); + *(outbuffer + offset++) = ranges_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_rangesi; + u_rangesi.real = this->ranges[i]; + *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ranges[i]); + } + *(outbuffer + offset++) = intensities_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_intensitiesi; + u_intensitiesi.real = this->intensities[i]; + *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensities[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.base = 0; + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_min = u_angle_min.real; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.base = 0; + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_max = u_angle_max.real; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.base = 0; + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_increment = u_angle_increment.real; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.base = 0; + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->time_increment = u_time_increment.real; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.base = 0; + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scan_time = u_scan_time.real; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.base = 0; + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_min = u_range_min.real; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.base = 0; + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_max = u_range_max.real; + offset += sizeof(this->range_max); + uint8_t ranges_lengthT = *(inbuffer + offset++); + if(ranges_lengthT > ranges_length) + this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float)); + offset += 3; + ranges_length = ranges_lengthT; + for( uint8_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_st_ranges; + u_st_ranges.base = 0; + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ranges = u_st_ranges.real; + offset += sizeof(this->st_ranges); + memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float)); + } + uint8_t intensities_lengthT = *(inbuffer + offset++); + if(intensities_lengthT > intensities_length) + this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float)); + offset += 3; + intensities_length = intensities_lengthT; + for( uint8_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_st_intensities; + u_st_intensities.base = 0; + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_intensities = u_st_intensities.real; + offset += sizeof(this->st_intensities); + memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float)); + } + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/LaserScan"; }; + virtual const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/MultiDOFJointState.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_sensor_msgs_MultiDOFJointState_h +#define _ROS_sensor_msgs_MultiDOFJointState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Transform.h" +#include "geometry_msgs/Twist.h" +#include "geometry_msgs/Wrench.h" + +namespace sensor_msgs +{ + + class MultiDOFJointState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t transforms_length; + geometry_msgs::Transform st_transforms; + geometry_msgs::Transform * transforms; + uint8_t twist_length; + geometry_msgs::Twist st_twist; + geometry_msgs::Twist * twist; + uint8_t wrench_length; + geometry_msgs::Wrench st_wrench; + geometry_msgs::Wrench * wrench; + + MultiDOFJointState(): + header(), + joint_names_length(0), joint_names(NULL), + transforms_length(0), transforms(NULL), + twist_length(0), twist(NULL), + wrench_length(0), wrench(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = twist_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->twist[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = wrench_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < wrench_length; i++){ + offset += this->wrench[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t transforms_lengthT = *(inbuffer + offset++); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform)); + offset += 3; + transforms_length = transforms_lengthT; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform)); + } + uint8_t twist_lengthT = *(inbuffer + offset++); + if(twist_lengthT > twist_length) + this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + twist_length = twist_lengthT; + for( uint8_t i = 0; i < twist_length; i++){ + offset += this->st_twist.deserialize(inbuffer + offset); + memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); + } + uint8_t wrench_lengthT = *(inbuffer + offset++); + if(wrench_lengthT > wrench_length) + this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench)); + offset += 3; + wrench_length = wrench_lengthT; + for( uint8_t i = 0; i < wrench_length; i++){ + offset += this->st_wrench.deserialize(inbuffer + offset); + memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/MultiDOFJointState"; }; + const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatFix.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,161 @@ +#ifndef _ROS_sensor_msgs_NavSatFix_h +#define _ROS_sensor_msgs_NavSatFix_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/NavSatStatus.h" + +namespace sensor_msgs +{ + + class NavSatFix : public ros::Msg + { + public: + std_msgs::Header header; + sensor_msgs::NavSatStatus status; + float latitude; + float longitude; + float altitude; + float position_covariance[9]; + uint8_t position_covariance_type; + enum { COVARIANCE_TYPE_UNKNOWN = 0 }; + enum { COVARIANCE_TYPE_APPROXIMATED = 1 }; + enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 }; + enum { COVARIANCE_TYPE_KNOWN = 3 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + int32_t * val_latitude = (long *) &(this->latitude); + int32_t exp_latitude = (((*val_latitude)>>23)&255); + if(exp_latitude != 0) + exp_latitude += 1023-127; + int32_t sig_latitude = *val_latitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_latitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_latitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_latitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_latitude<<4) & 0xF0) | ((sig_latitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_latitude>>4) & 0x7F; + if(this->latitude < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_longitude = (long *) &(this->longitude); + int32_t exp_longitude = (((*val_longitude)>>23)&255); + if(exp_longitude != 0) + exp_longitude += 1023-127; + int32_t sig_longitude = *val_longitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_longitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_longitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_longitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_longitude<<4) & 0xF0) | ((sig_longitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_longitude>>4) & 0x7F; + if(this->longitude < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_altitude = (long *) &(this->altitude); + int32_t exp_altitude = (((*val_altitude)>>23)&255); + if(exp_altitude != 0) + exp_altitude += 1023-127; + int32_t sig_altitude = *val_altitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_altitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_altitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_altitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_altitude<<4) & 0xF0) | ((sig_altitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_altitude>>4) & 0x7F; + if(this->altitude < 0) *(outbuffer + offset -1) |= 0x80; + unsigned char * position_covariance_val = (unsigned char *) this->position_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_position_covariancei = (long *) &(this->position_covariance[i]); + int32_t exp_position_covariancei = (((*val_position_covariancei)>>23)&255); + if(exp_position_covariancei != 0) + exp_position_covariancei += 1023-127; + int32_t sig_position_covariancei = *val_position_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_position_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_position_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_position_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_position_covariancei<<4) & 0xF0) | ((sig_position_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_position_covariancei>>4) & 0x7F; + if(this->position_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset + 0) = (this->position_covariance_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->position_covariance_type); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + uint32_t * val_latitude = (uint32_t*) &(this->latitude); + offset += 3; + *val_latitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_latitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_latitude !=0) + *val_latitude |= ((exp_latitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->latitude = -this->latitude; + uint32_t * val_longitude = (uint32_t*) &(this->longitude); + offset += 3; + *val_longitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_longitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_longitude !=0) + *val_longitude |= ((exp_longitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->longitude = -this->longitude; + uint32_t * val_altitude = (uint32_t*) &(this->altitude); + offset += 3; + *val_altitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_altitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_altitude !=0) + *val_altitude |= ((exp_altitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->altitude = -this->altitude; + uint8_t * position_covariance_val = (uint8_t*) this->position_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_position_covariancei = (uint32_t*) &(this->position_covariance[i]); + offset += 3; + *val_position_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_position_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_position_covariancei !=0) + *val_position_covariancei |= ((exp_position_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->position_covariance[i] = -this->position_covariance[i]; + } + this->position_covariance_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->position_covariance_type); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/NavSatFix"; }; + virtual const char * getMD5(){ return "2d3a8cd499b9b4a0249fb98fd05cfa48"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_sensor_msgs_NavSatStatus_h +#define _ROS_sensor_msgs_NavSatStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class NavSatStatus : public ros::Msg + { + public: + int8_t status; + uint16_t service; + enum { STATUS_NO_FIX = -1 }; + enum { STATUS_FIX = 0 }; + enum { STATUS_SBAS_FIX = 1 }; + enum { STATUS_GBAS_FIX = 2 }; + enum { SERVICE_GPS = 1 }; + enum { SERVICE_GLONASS = 2 }; + enum { SERVICE_COMPASS = 4 }; + enum { SERVICE_GALILEO = 8 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.real = this->status; + *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->status); + *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF; + offset += sizeof(this->service); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.base = 0; + u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->status = u_status.real; + offset += sizeof(this->status); + this->service |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->service); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/NavSatStatus"; }; + virtual const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,85 @@ +#ifndef _ROS_sensor_msgs_PointCloud_h +#define _ROS_sensor_msgs_PointCloud_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point32.h" +#include "sensor_msgs/ChannelFloat32.h" + +namespace sensor_msgs +{ + + class PointCloud : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t points_length; + geometry_msgs::Point32 st_points; + geometry_msgs::Point32 * points; + uint8_t channels_length; + sensor_msgs::ChannelFloat32 st_channels; + sensor_msgs::ChannelFloat32 * channels; + + PointCloud(): + header(), + points_length(0), points(NULL), + channels_length(0), channels(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = channels_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < channels_length; i++){ + offset += this->channels[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); + } + uint8_t channels_lengthT = *(inbuffer + offset++); + if(channels_lengthT > channels_length) + this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32)); + offset += 3; + channels_length = channels_lengthT; + for( uint8_t i = 0; i < channels_length; i++){ + offset += this->st_channels.deserialize(inbuffer + offset); + memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/PointCloud"; }; + const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud2.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,155 @@ +#ifndef _ROS_sensor_msgs_PointCloud2_h +#define _ROS_sensor_msgs_PointCloud2_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/PointField.h" + +namespace sensor_msgs +{ + + class PointCloud2 : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + uint8_t fields_length; + sensor_msgs::PointField st_fields; + sensor_msgs::PointField * fields; + bool is_bigendian; + uint32_t point_step; + uint32_t row_step; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + bool is_dense; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset++) = fields_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fields_length; i++){ + offset += this->fields[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.real = this->is_bigendian; + *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->point_step); + *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->row_step); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.real = this->is_dense; + *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_dense); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint8_t fields_lengthT = *(inbuffer + offset++); + if(fields_lengthT > fields_length) + this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField)); + offset += 3; + fields_length = fields_lengthT; + for( uint8_t i = 0; i < fields_length; i++){ + offset += this->st_fields.deserialize(inbuffer + offset); + memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField)); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.base = 0; + u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_bigendian = u_is_bigendian.real; + offset += sizeof(this->is_bigendian); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->point_step); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->row_step); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.base = 0; + u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_dense = u_is_dense.real; + offset += sizeof(this->is_dense); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/PointCloud2"; }; + virtual const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointField.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,83 @@ +#ifndef _ROS_sensor_msgs_PointField_h +#define _ROS_sensor_msgs_PointField_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class PointField : public ros::Msg + { + public: + char * name; + uint32_t offset; + uint8_t datatype; + uint32_t count; + enum { INT8 = 1 }; + enum { UINT8 = 2 }; + enum { INT16 = 3 }; + enum { UINT16 = 4 }; + enum { INT32 = 5 }; + enum { UINT32 = 6 }; + enum { FLOAT32 = 7 }; + enum { FLOAT64 = 8 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t * length_name = (uint32_t *)(outbuffer + offset); + *length_name = strlen( (const char*) this->name); + offset += 4; + memcpy(outbuffer + offset, this->name, *length_name); + offset += *length_name; + *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->offset); + *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; + offset += sizeof(this->datatype); + *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; + offset += sizeof(this->count); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + this->offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->offset); + this->datatype |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->datatype); + this->count |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->count); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/PointField"; }; + virtual const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Range.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,133 @@ +#ifndef _ROS_sensor_msgs_Range_h +#define _ROS_sensor_msgs_Range_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Range : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t radiation_type; + float field_of_view; + float min_range; + float max_range; + float range; + enum { ULTRASOUND = 0 }; + enum { INFRARED = 1 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.real = this->field_of_view; + *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.real = this->min_range; + *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.real = this->max_range; + *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.real = this->range; + *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->radiation_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.base = 0; + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->field_of_view = u_field_of_view.real; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.base = 0; + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_range = u_min_range.real; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.base = 0; + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_range = u_max_range.real; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.base = 0; + u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range = u_range.real; + offset += sizeof(this->range); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/Range"; }; + virtual const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/RegionOfInterest.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,94 @@ +#ifndef _ROS_sensor_msgs_RegionOfInterest_h +#define _ROS_sensor_msgs_RegionOfInterest_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class RegionOfInterest : public ros::Msg + { + public: + uint32_t x_offset; + uint32_t y_offset; + uint32_t height; + uint32_t width; + bool do_rectify; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->x_offset); + *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->y_offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.real = this->do_rectify; + *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->do_rectify); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->x_offset); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->y_offset); + this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.base = 0; + u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->do_rectify = u_do_rectify.real; + offset += sizeof(this->do_rectify); + return offset; + } + + virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; }; + virtual const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/RelativeHumidity.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,51 @@ +#ifndef _ROS_sensor_msgs_RelativeHumidity_h +#define _ROS_sensor_msgs_RelativeHumidity_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class RelativeHumidity : public ros::Msg + { + public: + std_msgs::Header header; + float relative_humidity; + float variance; + + RelativeHumidity(): + header(), + relative_humidity(0), + variance(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += serializeAvrFloat64(outbuffer + offset, this->relative_humidity); + offset += serializeAvrFloat64(outbuffer + offset, this->variance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->relative_humidity)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); + return offset; + } + + const char * getType(){ return "sensor_msgs/RelativeHumidity"; }; + const char * getMD5(){ return "8730015b05955b7e992ce29a2678d90f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/SetCameraInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_SERVICE_SetCameraInfo_h +#define _ROS_SERVICE_SetCameraInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/CameraInfo.h" + +namespace sensor_msgs +{ + +static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo"; + + class SetCameraInfoRequest : public ros::Msg + { + public: + sensor_msgs::CameraInfo camera_info; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->camera_info.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->camera_info.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return SETCAMERAINFO; }; + virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; }; + + }; + + class SetCameraInfoResponse : public ros::Msg + { + public: + bool success; + char * status_message; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t * length_status_message = (uint32_t *)(outbuffer + offset); + *length_status_message = strlen( (const char*) this->status_message); + offset += 4; + memcpy(outbuffer + offset, this->status_message, *length_status_message); + offset += *length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + virtual const char * getType(){ return SETCAMERAINFO; }; + virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetCameraInfo { + public: + typedef SetCameraInfoRequest Request; + typedef SetCameraInfoResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/shape_msgs/Mesh.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_shape_msgs_Mesh_h +#define _ROS_shape_msgs_Mesh_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "shape_msgs/MeshTriangle.h" +#include "geometry_msgs/Point.h" + +namespace shape_msgs +{ + + class Mesh : public ros::Msg + { + public: + uint8_t triangles_length; + shape_msgs::MeshTriangle st_triangles; + shape_msgs::MeshTriangle * triangles; + uint8_t vertices_length; + geometry_msgs::Point st_vertices; + geometry_msgs::Point * vertices; + + Mesh(): + triangles_length(0), triangles(NULL), + vertices_length(0), vertices(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = triangles_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < triangles_length; i++){ + offset += this->triangles[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = vertices_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < vertices_length; i++){ + offset += this->vertices[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t triangles_lengthT = *(inbuffer + offset++); + if(triangles_lengthT > triangles_length) + this->triangles = (shape_msgs::MeshTriangle*)realloc(this->triangles, triangles_lengthT * sizeof(shape_msgs::MeshTriangle)); + offset += 3; + triangles_length = triangles_lengthT; + for( uint8_t i = 0; i < triangles_length; i++){ + offset += this->st_triangles.deserialize(inbuffer + offset); + memcpy( &(this->triangles[i]), &(this->st_triangles), sizeof(shape_msgs::MeshTriangle)); + } + uint8_t vertices_lengthT = *(inbuffer + offset++); + if(vertices_lengthT > vertices_length) + this->vertices = (geometry_msgs::Point*)realloc(this->vertices, vertices_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + vertices_length = vertices_lengthT; + for( uint8_t i = 0; i < vertices_length; i++){ + offset += this->st_vertices.deserialize(inbuffer + offset); + memcpy( &(this->vertices[i]), &(this->st_vertices), sizeof(geometry_msgs::Point)); + } + return offset; + } + + const char * getType(){ return "shape_msgs/Mesh"; }; + const char * getMD5(){ return "1ffdae9486cd3316a121c578b47a85cc"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/shape_msgs/MeshTriangle.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,18 @@ +#ifndef _ROS_shape_msgs_MeshTriangle_h +#define _ROS_shape_msgs_MeshTriangle_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace shape_msgs +{ + + class MeshTriangle : public ros::Msg + { + public: + uint32_t vertex_indices[3]; + + MeshTriangle(): +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/smach_msgs/SmachContainerInitialStatusCmd.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,102 @@ +#ifndef _ROS_smach_msgs_SmachContainerInitialStatusCmd_h +#define _ROS_smach_msgs_SmachContainerInitialStatusCmd_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace smach_msgs +{ + + class SmachContainerInitialStatusCmd : public ros::Msg + { + public: + const char* path; + uint8_t initial_states_length; + char* st_initial_states; + char* * initial_states; + const char* local_data; + + SmachContainerInitialStatusCmd(): + path(""), + initial_states_length(0), initial_states(NULL), + local_data("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_path = strlen(this->path); + memcpy(outbuffer + offset, &length_path, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->path, length_path); + offset += length_path; + *(outbuffer + offset++) = initial_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < initial_states_length; i++){ + uint32_t length_initial_statesi = strlen(this->initial_states[i]); + memcpy(outbuffer + offset, &length_initial_statesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi); + offset += length_initial_statesi; + } + uint32_t length_local_data = strlen(this->local_data); + memcpy(outbuffer + offset, &length_local_data, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->local_data, length_local_data); + offset += length_local_data; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_path; + memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_path; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_path-1]=0; + this->path = (char *)(inbuffer + offset-1); + offset += length_path; + uint8_t initial_states_lengthT = *(inbuffer + offset++); + if(initial_states_lengthT > initial_states_length) + this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*)); + offset += 3; + initial_states_length = initial_states_lengthT; + for( uint8_t i = 0; i < initial_states_length; i++){ + uint32_t length_st_initial_states; + memcpy(&length_st_initial_states, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_initial_states; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_initial_states-1]=0; + this->st_initial_states = (char *)(inbuffer + offset-1); + offset += length_st_initial_states; + memcpy( &(this->initial_states[i]), &(this->st_initial_states), sizeof(char*)); + } + uint32_t length_local_data; + memcpy(&length_local_data, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_local_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_local_data-1]=0; + this->local_data = (char *)(inbuffer + offset-1); + offset += length_local_data; + return offset; + } + + const char * getType(){ return "smach_msgs/SmachContainerInitialStatusCmd"; }; + const char * getMD5(){ return "45f8cf31fc29b829db77f23001f788d6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/smach_msgs/SmachContainerStatus.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,155 @@ +#ifndef _ROS_smach_msgs_SmachContainerStatus_h +#define _ROS_smach_msgs_SmachContainerStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace smach_msgs +{ + + class SmachContainerStatus : public ros::Msg + { + public: + std_msgs::Header header; + const char* path; + uint8_t initial_states_length; + char* st_initial_states; + char* * initial_states; + uint8_t active_states_length; + char* st_active_states; + char* * active_states; + const char* local_data; + const char* info; + + SmachContainerStatus(): + header(), + path(""), + initial_states_length(0), initial_states(NULL), + active_states_length(0), active_states(NULL), + local_data(""), + info("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_path = strlen(this->path); + memcpy(outbuffer + offset, &length_path, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->path, length_path); + offset += length_path; + *(outbuffer + offset++) = initial_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < initial_states_length; i++){ + uint32_t length_initial_statesi = strlen(this->initial_states[i]); + memcpy(outbuffer + offset, &length_initial_statesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi); + offset += length_initial_statesi; + } + *(outbuffer + offset++) = active_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < active_states_length; i++){ + uint32_t length_active_statesi = strlen(this->active_states[i]); + memcpy(outbuffer + offset, &length_active_statesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->active_states[i], length_active_statesi); + offset += length_active_statesi; + } + uint32_t length_local_data = strlen(this->local_data); + memcpy(outbuffer + offset, &length_local_data, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->local_data, length_local_data); + offset += length_local_data; + uint32_t length_info = strlen(this->info); + memcpy(outbuffer + offset, &length_info, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->info, length_info); + offset += length_info; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_path; + memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_path; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_path-1]=0; + this->path = (char *)(inbuffer + offset-1); + offset += length_path; + uint8_t initial_states_lengthT = *(inbuffer + offset++); + if(initial_states_lengthT > initial_states_length) + this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*)); + offset += 3; + initial_states_length = initial_states_lengthT; + for( uint8_t i = 0; i < initial_states_length; i++){ + uint32_t length_st_initial_states; + memcpy(&length_st_initial_states, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_initial_states; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_initial_states-1]=0; + this->st_initial_states = (char *)(inbuffer + offset-1); + offset += length_st_initial_states; + memcpy( &(this->initial_states[i]), &(this->st_initial_states), sizeof(char*)); + } + uint8_t active_states_lengthT = *(inbuffer + offset++); + if(active_states_lengthT > active_states_length) + this->active_states = (char**)realloc(this->active_states, active_states_lengthT * sizeof(char*)); + offset += 3; + active_states_length = active_states_lengthT; + for( uint8_t i = 0; i < active_states_length; i++){ + uint32_t length_st_active_states; + memcpy(&length_st_active_states, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_active_states; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_active_states-1]=0; + this->st_active_states = (char *)(inbuffer + offset-1); + offset += length_st_active_states; + memcpy( &(this->active_states[i]), &(this->st_active_states), sizeof(char*)); + } + uint32_t length_local_data; + memcpy(&length_local_data, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_local_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_local_data-1]=0; + this->local_data = (char *)(inbuffer + offset-1); + offset += length_local_data; + uint32_t length_info; + memcpy(&length_info, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_info; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_info-1]=0; + this->info = (char *)(inbuffer + offset-1); + offset += length_info; + return offset; + } + + const char * getType(){ return "smach_msgs/SmachContainerStatus"; }; + const char * getMD5(){ return "5ba2bb79ac19e3842d562a191f2a675b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/smach_msgs/SmachContainerStructure.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,219 @@ +#ifndef _ROS_smach_msgs_SmachContainerStructure_h +#define _ROS_smach_msgs_SmachContainerStructure_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace smach_msgs +{ + + class SmachContainerStructure : public ros::Msg + { + public: + std_msgs::Header header; + const char* path; + uint8_t children_length; + char* st_children; + char* * children; + uint8_t internal_outcomes_length; + char* st_internal_outcomes; + char* * internal_outcomes; + uint8_t outcomes_from_length; + char* st_outcomes_from; + char* * outcomes_from; + uint8_t outcomes_to_length; + char* st_outcomes_to; + char* * outcomes_to; + uint8_t container_outcomes_length; + char* st_container_outcomes; + char* * container_outcomes; + + SmachContainerStructure(): + header(), + path(""), + children_length(0), children(NULL), + internal_outcomes_length(0), internal_outcomes(NULL), + outcomes_from_length(0), outcomes_from(NULL), + outcomes_to_length(0), outcomes_to(NULL), + container_outcomes_length(0), container_outcomes(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_path = strlen(this->path); + memcpy(outbuffer + offset, &length_path, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->path, length_path); + offset += length_path; + *(outbuffer + offset++) = children_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < children_length; i++){ + uint32_t length_childreni = strlen(this->children[i]); + memcpy(outbuffer + offset, &length_childreni, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->children[i], length_childreni); + offset += length_childreni; + } + *(outbuffer + offset++) = internal_outcomes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < internal_outcomes_length; i++){ + uint32_t length_internal_outcomesi = strlen(this->internal_outcomes[i]); + memcpy(outbuffer + offset, &length_internal_outcomesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->internal_outcomes[i], length_internal_outcomesi); + offset += length_internal_outcomesi; + } + *(outbuffer + offset++) = outcomes_from_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < outcomes_from_length; i++){ + uint32_t length_outcomes_fromi = strlen(this->outcomes_from[i]); + memcpy(outbuffer + offset, &length_outcomes_fromi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->outcomes_from[i], length_outcomes_fromi); + offset += length_outcomes_fromi; + } + *(outbuffer + offset++) = outcomes_to_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < outcomes_to_length; i++){ + uint32_t length_outcomes_toi = strlen(this->outcomes_to[i]); + memcpy(outbuffer + offset, &length_outcomes_toi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->outcomes_to[i], length_outcomes_toi); + offset += length_outcomes_toi; + } + *(outbuffer + offset++) = container_outcomes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < container_outcomes_length; i++){ + uint32_t length_container_outcomesi = strlen(this->container_outcomes[i]); + memcpy(outbuffer + offset, &length_container_outcomesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->container_outcomes[i], length_container_outcomesi); + offset += length_container_outcomesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_path; + memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_path; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_path-1]=0; + this->path = (char *)(inbuffer + offset-1); + offset += length_path; + uint8_t children_lengthT = *(inbuffer + offset++); + if(children_lengthT > children_length) + this->children = (char**)realloc(this->children, children_lengthT * sizeof(char*)); + offset += 3; + children_length = children_lengthT; + for( uint8_t i = 0; i < children_length; i++){ + uint32_t length_st_children; + memcpy(&length_st_children, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_children; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_children-1]=0; + this->st_children = (char *)(inbuffer + offset-1); + offset += length_st_children; + memcpy( &(this->children[i]), &(this->st_children), sizeof(char*)); + } + uint8_t internal_outcomes_lengthT = *(inbuffer + offset++); + if(internal_outcomes_lengthT > internal_outcomes_length) + this->internal_outcomes = (char**)realloc(this->internal_outcomes, internal_outcomes_lengthT * sizeof(char*)); + offset += 3; + internal_outcomes_length = internal_outcomes_lengthT; + for( uint8_t i = 0; i < internal_outcomes_length; i++){ + uint32_t length_st_internal_outcomes; + memcpy(&length_st_internal_outcomes, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_internal_outcomes; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_internal_outcomes-1]=0; + this->st_internal_outcomes = (char *)(inbuffer + offset-1); + offset += length_st_internal_outcomes; + memcpy( &(this->internal_outcomes[i]), &(this->st_internal_outcomes), sizeof(char*)); + } + uint8_t outcomes_from_lengthT = *(inbuffer + offset++); + if(outcomes_from_lengthT > outcomes_from_length) + this->outcomes_from = (char**)realloc(this->outcomes_from, outcomes_from_lengthT * sizeof(char*)); + offset += 3; + outcomes_from_length = outcomes_from_lengthT; + for( uint8_t i = 0; i < outcomes_from_length; i++){ + uint32_t length_st_outcomes_from; + memcpy(&length_st_outcomes_from, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_outcomes_from; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_outcomes_from-1]=0; + this->st_outcomes_from = (char *)(inbuffer + offset-1); + offset += length_st_outcomes_from; + memcpy( &(this->outcomes_from[i]), &(this->st_outcomes_from), sizeof(char*)); + } + uint8_t outcomes_to_lengthT = *(inbuffer + offset++); + if(outcomes_to_lengthT > outcomes_to_length) + this->outcomes_to = (char**)realloc(this->outcomes_to, outcomes_to_lengthT * sizeof(char*)); + offset += 3; + outcomes_to_length = outcomes_to_lengthT; + for( uint8_t i = 0; i < outcomes_to_length; i++){ + uint32_t length_st_outcomes_to; + memcpy(&length_st_outcomes_to, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_outcomes_to; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_outcomes_to-1]=0; + this->st_outcomes_to = (char *)(inbuffer + offset-1); + offset += length_st_outcomes_to; + memcpy( &(this->outcomes_to[i]), &(this->st_outcomes_to), sizeof(char*)); + } + uint8_t container_outcomes_lengthT = *(inbuffer + offset++); + if(container_outcomes_lengthT > container_outcomes_length) + this->container_outcomes = (char**)realloc(this->container_outcomes, container_outcomes_lengthT * sizeof(char*)); + offset += 3; + container_outcomes_length = container_outcomes_lengthT; + for( uint8_t i = 0; i < container_outcomes_length; i++){ + uint32_t length_st_container_outcomes; + memcpy(&length_st_container_outcomes, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_container_outcomes; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_container_outcomes-1]=0; + this->st_container_outcomes = (char *)(inbuffer + offset-1); + offset += length_st_container_outcomes; + memcpy( &(this->container_outcomes[i]), &(this->st_container_outcomes), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "smach_msgs/SmachContainerStructure"; }; + const char * getMD5(){ return "3d3d1e0d0f99779ee9e58101a5dcf7ea"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Bool.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,55 @@ +#ifndef _ROS_std_msgs_Bool_h +#define _ROS_std_msgs_Bool_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Bool : public ros::Msg + { + public: + bool data; + + Bool(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Bool"; }; + const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Byte.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,55 @@ +#ifndef _ROS_std_msgs_Byte_h +#define _ROS_std_msgs_Byte_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Byte : public ros::Msg + { + public: + int8_t data; + + Byte(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Byte"; }; + const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ByteMultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_ByteMultiArray_h +#define _ROS_std_msgs_ByteMultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class ByteMultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + ByteMultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/ByteMultiArray"; }; + const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Char.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,44 @@ +#ifndef _ROS_std_msgs_Char_h +#define _ROS_std_msgs_Char_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Char : public ros::Msg + { + public: + uint8_t data; + + Char(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Char"; }; + const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ColorRGBA.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,130 @@ +#ifndef _ROS_std_msgs_ColorRGBA_h +#define _ROS_std_msgs_ColorRGBA_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class ColorRGBA : public ros::Msg + { + public: + float r; + float g; + float b; + float a; + + ColorRGBA(): + r(0), + g(0), + b(0), + a(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.real = this->r; + *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.real = this->g; + *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->a); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.base = 0; + u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->r = u_r.real; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.base = 0; + u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->g = u_g.real; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b = u_b.real; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->a = u_a.real; + offset += sizeof(this->a); + return offset; + } + + const char * getType(){ return "std_msgs/ColorRGBA"; }; + const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Duration.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_Duration_h +#define _ROS_std_msgs_Duration_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace std_msgs +{ + + class Duration : public ros::Msg + { + public: + ros::Duration data; + + Duration(): + data() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Duration"; }; + const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Empty.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_std_msgs_Empty_h +#define _ROS_std_msgs_Empty_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Empty : public ros::Msg + { + public: + + Empty() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "std_msgs/Empty"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_Float32_h +#define _ROS_std_msgs_Float32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float32 : public ros::Msg + { + public: + float data; + + Float32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Float32"; }; + const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_Float32MultiArray_h +#define _ROS_std_msgs_Float32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + Float32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float32MultiArray"; }; + const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_std_msgs_Float64_h +#define _ROS_std_msgs_Float64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float64 : public ros::Msg + { + public: + float data; + + Float64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->data)); + return offset; + } + + const char * getType(){ return "std_msgs/Float64"; }; + const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,63 @@ +#ifndef _ROS_std_msgs_Float64MultiArray_h +#define _ROS_std_msgs_Float64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + Float64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_data)); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float64MultiArray"; }; + const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Header.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,89 @@ +#ifndef _ROS_std_msgs_Header_h +#define _ROS_std_msgs_Header_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Header : public ros::Msg + { + public: + uint32_t seq; + ros::Time stamp; + const char* frame_id; + + Header(): + seq(0), + stamp(), + frame_id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq); + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id = strlen(this->frame_id); + memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->frame_id, length_frame_id); + offset += length_frame_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->seq = ((uint32_t) (*(inbuffer + offset))); + this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->seq); + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id; + memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_id-1]=0; + this->frame_id = (char *)(inbuffer + offset-1); + offset += length_frame_id; + return offset; + } + + const char * getType(){ return "std_msgs/Header"; }; + const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,57 @@ +#ifndef _ROS_std_msgs_Int16_h +#define _ROS_std_msgs_Int16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int16 : public ros::Msg + { + public: + int16_t data; + + Int16(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int16"; }; + const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_std_msgs_Int16MultiArray_h +#define _ROS_std_msgs_Int16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int16MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int16_t st_data; + int16_t * data; + + Int16MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int16MultiArray"; }; + const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_Int32_h +#define _ROS_std_msgs_Int32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int32 : public ros::Msg + { + public: + int32_t data; + + Int32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int32"; }; + const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_Int32MultiArray_h +#define _ROS_std_msgs_Int32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int32_t st_data; + int32_t * data; + + Int32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int32MultiArray"; }; + const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +#ifndef _ROS_std_msgs_Int64_h +#define _ROS_std_msgs_Int64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int64 : public ros::Msg + { + public: + int64_t data; + + Int64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int64"; }; + const char * getMD5(){ return "34add168574510e6e17f5d23ecc077ef"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,90 @@ +#ifndef _ROS_std_msgs_Int64MultiArray_h +#define _ROS_std_msgs_Int64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int64_t st_data; + int64_t * data; + + Int64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int64MultiArray"; }; + const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,55 @@ +#ifndef _ROS_std_msgs_Int8_h +#define _ROS_std_msgs_Int8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int8 : public ros::Msg + { + public: + int8_t data; + + Int8(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int8"; }; + const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_Int8MultiArray_h +#define _ROS_std_msgs_Int8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int8MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + Int8MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int8MultiArray"; }; + const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayDimension.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_std_msgs_MultiArrayDimension_h +#define _ROS_std_msgs_MultiArrayDimension_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class MultiArrayDimension : public ros::Msg + { + public: + const char* label; + uint32_t size; + uint32_t stride; + + MultiArrayDimension(): + label(""), + size(0), + stride(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_label = strlen(this->label); + memcpy(outbuffer + offset, &length_label, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->label, length_label); + offset += length_label; + *(outbuffer + offset + 0) = (this->size >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size >> (8 * 3)) & 0xFF; + offset += sizeof(this->size); + *(outbuffer + offset + 0) = (this->stride >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stride >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stride >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stride >> (8 * 3)) & 0xFF; + offset += sizeof(this->stride); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_label; + memcpy(&length_label, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_label; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_label-1]=0; + this->label = (char *)(inbuffer + offset-1); + offset += length_label; + this->size = ((uint32_t) (*(inbuffer + offset))); + this->size |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size); + this->stride = ((uint32_t) (*(inbuffer + offset))); + this->stride |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stride |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stride |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stride); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayDimension"; }; + const char * getMD5(){ return "4cd0c83a8683deae40ecdac60e53bfa8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayLayout.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_std_msgs_MultiArrayLayout_h +#define _ROS_std_msgs_MultiArrayLayout_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayDimension.h" + +namespace std_msgs +{ + + class MultiArrayLayout : public ros::Msg + { + public: + uint8_t dim_length; + std_msgs::MultiArrayDimension st_dim; + std_msgs::MultiArrayDimension * dim; + uint32_t data_offset; + + MultiArrayLayout(): + dim_length(0), dim(NULL), + data_offset(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = dim_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < dim_length; i++){ + offset += this->dim[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->data_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t dim_lengthT = *(inbuffer + offset++); + if(dim_lengthT > dim_length) + this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension)); + offset += 3; + dim_length = dim_lengthT; + for( uint8_t i = 0; i < dim_length; i++){ + offset += this->st_dim.deserialize(inbuffer + offset); + memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension)); + } + this->data_offset = ((uint32_t) (*(inbuffer + offset))); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_offset); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayLayout"; }; + const char * getMD5(){ return "0fed2a11c13e11c5571b4e2a995a91a3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/String.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_std_msgs_String_h +#define _ROS_std_msgs_String_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class String : public ros::Msg + { + public: + const char* data; + + String(): + data("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_data = strlen(this->data); + memcpy(outbuffer + offset, &length_data, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->data, length_data); + offset += length_data; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_data; + memcpy(&length_data, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_data-1]=0; + this->data = (char *)(inbuffer + offset-1); + offset += length_data; + return offset; + } + + const char * getType(){ return "std_msgs/String"; }; + const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Time.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_Time_h +#define _ROS_std_msgs_Time_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Time : public ros::Msg + { + public: + ros::Time data; + + Time(): + data() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Time"; }; + const char * getMD5(){ return "cd7166c74c552c311fbcc2fe5a7bc289"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,46 @@ +#ifndef _ROS_std_msgs_UInt16_h +#define _ROS_std_msgs_UInt16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt16 : public ros::Msg + { + public: + uint16_t data; + + UInt16(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint16_t) (*(inbuffer + offset))); + this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt16"; }; + const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_std_msgs_UInt16MultiArray_h +#define _ROS_std_msgs_UInt16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt16MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint16_t st_data; + uint16_t * data; + + UInt16MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint16_t) (*(inbuffer + offset))); + this->st_data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt16MultiArray"; }; + const char * getMD5(){ return "52f264f1c973c4b73790d384c6cb4484"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_UInt32_h +#define _ROS_std_msgs_UInt32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt32 : public ros::Msg + { + public: + uint32_t data; + + UInt32(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint32_t) (*(inbuffer + offset))); + this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt32"; }; + const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_std_msgs_UInt32MultiArray_h +#define _ROS_std_msgs_UInt32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint32_t st_data; + uint32_t * data; + + UInt32MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint32_t) (*(inbuffer + offset))); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt32MultiArray"; }; + const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_UInt64_h +#define _ROS_std_msgs_UInt64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt64 : public ros::Msg + { + public: + uint64_t data; + + UInt64(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt64"; }; + const char * getMD5(){ return "1b2a79973e8bf53d7b53acb71299cb57"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_UInt64MultiArray_h +#define _ROS_std_msgs_UInt64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint64_t st_data; + uint64_t * data; + + UInt64MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt64MultiArray"; }; + const char * getMD5(){ return "6088f127afb1d6c72927aa1247e945af"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,44 @@ +#ifndef _ROS_std_msgs_UInt8_h +#define _ROS_std_msgs_UInt8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt8 : public ros::Msg + { + public: + uint8_t data; + + UInt8(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt8"; }; + const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8MultiArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_std_msgs_UInt8MultiArray_h +#define _ROS_std_msgs_UInt8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt8MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + UInt8MultiArray(): + layout(), + data_length(0), data(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt8MultiArray"; }; + const char * getMD5(){ return "82373f1612381bb6ee473b5cd6f5d89c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_srvs/Empty.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_SERVICE_Empty_h +#define _ROS_SERVICE_Empty_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_srvs +{ + +static const char EMPTY[] = "std_srvs/Empty"; + + class EmptyRequest : public ros::Msg + { + public: + + EmptyRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class EmptyResponse : public ros::Msg + { + public: + + EmptyResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class Empty { + public: + typedef EmptyRequest Request; + typedef EmptyResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stereo_msgs/DisparityImage.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,168 @@ +#ifndef _ROS_stereo_msgs_DisparityImage_h +#define _ROS_stereo_msgs_DisparityImage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/Image.h" +#include "sensor_msgs/RegionOfInterest.h" + +namespace stereo_msgs +{ + + class DisparityImage : public ros::Msg + { + public: + std_msgs::Header header; + sensor_msgs::Image image; + float f; + float T; + sensor_msgs::RegionOfInterest valid_window; + float min_disparity; + float max_disparity; + float delta_d; + + DisparityImage(): + header(), + image(), + f(0), + T(0), + valid_window(), + min_disparity(0), + max_disparity(0), + delta_d(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->image.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_f; + u_f.real = this->f; + *(outbuffer + offset + 0) = (u_f.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_f.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_f.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_f.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->f); + union { + float real; + uint32_t base; + } u_T; + u_T.real = this->T; + *(outbuffer + offset + 0) = (u_T.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_T.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_T.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_T.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->T); + offset += this->valid_window.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_min_disparity; + u_min_disparity.real = this->min_disparity; + *(outbuffer + offset + 0) = (u_min_disparity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_disparity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_disparity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_disparity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_disparity); + union { + float real; + uint32_t base; + } u_max_disparity; + u_max_disparity.real = this->max_disparity; + *(outbuffer + offset + 0) = (u_max_disparity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_disparity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_disparity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_disparity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_disparity); + union { + float real; + uint32_t base; + } u_delta_d; + u_delta_d.real = this->delta_d; + *(outbuffer + offset + 0) = (u_delta_d.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_delta_d.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_delta_d.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_delta_d.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->delta_d); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->image.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_f; + u_f.base = 0; + u_f.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_f.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_f.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_f.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->f = u_f.real; + offset += sizeof(this->f); + union { + float real; + uint32_t base; + } u_T; + u_T.base = 0; + u_T.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_T.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_T.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_T.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->T = u_T.real; + offset += sizeof(this->T); + offset += this->valid_window.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_min_disparity; + u_min_disparity.base = 0; + u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_disparity = u_min_disparity.real; + offset += sizeof(this->min_disparity); + union { + float real; + uint32_t base; + } u_max_disparity; + u_max_disparity.base = 0; + u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_disparity = u_max_disparity.real; + offset += sizeof(this->max_disparity); + union { + float real; + uint32_t base; + } u_delta_d; + u_delta_d.base = 0; + u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->delta_d = u_delta_d.real; + offset += sizeof(this->delta_d); + return offset; + } + + const char * getType(){ return "stereo_msgs/DisparityImage"; }; + const char * getMD5(){ return "04a177815f75271039fa21f16acad8c9"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tests/array_test.cpp Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,47 @@ +//#define COMPILE_ARRAY_CODE_RSOSSERIAL +#ifdef COMPILE_ARRAY_CODE_RSOSSERIAL + +/* + * rosserial::geometry_msgs::PoseArray Test + * Sums an array, publishes sum + */ +#include "mbed.h" +#include <ros.h> +#include <geometry_msgs/Pose.h> +#include <geometry_msgs/PoseArray.h> + + +ros::NodeHandle nh; + +bool set_; +DigitalOut myled(LED1); + +geometry_msgs::Pose sum_msg; +ros::Publisher p("sum", &sum_msg); + +void messageCb(const geometry_msgs::PoseArray& msg) { + sum_msg.position.x = 0; + sum_msg.position.y = 0; + sum_msg.position.z = 0; + for (int i = 0; i < msg.poses_length; i++) { + sum_msg.position.x += msg.poses[i].position.x; + sum_msg.position.y += msg.poses[i].position.y; + sum_msg.position.z += msg.poses[i].position.z; + } + myled = !myled; // blink the led +} + +ros::Subscriber<geometry_msgs::PoseArray> s("poses",messageCb); + +int main() { + nh.initNode(); + nh.subscribe(s); + nh.advertise(p); + + while (1) { + p.publish(&sum_msg); + nh.spinOnce(); + wait_ms(10); + } +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tests/float64_test.cpp Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,39 @@ +//#define COMPLIE_FLOAT64_CODE_ROSSERIAL +#ifdef COMPILE_FLOAT64_CODE_ROSSERIAL + +/* + * rosserial::std_msgs::Float64 Test + * Receives a Float64 input, subtracts 1.0, and publishes it + */ + +#include "mbed.h" +#include <ros.h> +#include <std_msgs/Float64.h> + + +ros::NodeHandle nh; + +float x; +DigitalOut myled(LED1); + +void messageCb( const std_msgs::Float64& msg) { + x = msg.data - 1.0; + myled = !myled; // blink the led +} + +std_msgs::Float64 test; +ros::Subscriber<std_msgs::Float64> s("your_topic", &messageCb); +ros::Publisher p("my_topic", &test); + +int main() { + nh.initNode(); + nh.advertise(p); + nh.subscribe(s); + while (1) { + test.data = x; + p.publish( &test ); + nh.spinOnce(); + wait_ms(10); + } +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tests/time_test.cpp Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,31 @@ +//#define COMPILE_TIME_CODE_ROSSERIAL +#ifdef COMPILE_TIME_CODE_ROSSERIAL + +/* + * rosserial::std_msgs::Time Test + * Publishes current time + */ + +#include "mbed.h" +#include <ros.h> +#include <ros/time.h> +#include <std_msgs/Time.h> + + +ros::NodeHandle nh; + +std_msgs::Time test; +ros::Publisher p("my_topic", &test); + +int main() { + nh.initNode(); + nh.advertise(p); + + while (1) { + test.data = nh.now(); + p.publish( &test ); + nh.spinOnce(); + wait_ms(10); + } +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/FrameGraph.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_FrameGraph_h +#define _ROS_SERVICE_FrameGraph_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace tf +{ + +static const char FRAMEGRAPH[] = "tf/FrameGraph"; + + class FrameGraphRequest : public ros::Msg + { + public: + + FrameGraphRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class FrameGraphResponse : public ros::Msg + { + public: + const char* dot_graph; + + FrameGraphResponse(): + dot_graph("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_dot_graph = strlen(this->dot_graph); + memcpy(outbuffer + offset, &length_dot_graph, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->dot_graph, length_dot_graph); + offset += length_dot_graph; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_dot_graph; + memcpy(&length_dot_graph, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_dot_graph; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_dot_graph-1]=0; + this->dot_graph = (char *)(inbuffer + offset-1); + offset += length_dot_graph; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "c4af9ac907e58e906eb0b6e3c58478c0"; }; + + }; + + class FrameGraph { + public: + typedef FrameGraphRequest Request; + typedef FrameGraphResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/tf.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,57 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TF_H_ +#define ROS_TF_H_ + +#include "geometry_msgs/TransformStamped.h" + +namespace tf +{ + + static inline geometry_msgs::Quaternion createQuaternionFromYaw(double yaw) + { + geometry_msgs::Quaternion q; + q.x = 0; + q.y = 0; + q.z = sin(yaw * 0.5); + q.w = cos(yaw * 0.5); + return q; + } + +} + +#endif + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/tfMessage.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_tf_tfMessage_h +#define _ROS_tf_tfMessage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/TransformStamped.h" + +namespace tf +{ + + class tfMessage : public ros::Msg + { + public: + uint8_t transforms_length; + geometry_msgs::TransformStamped st_transforms; + geometry_msgs::TransformStamped * transforms; + + tfMessage(): + transforms_length(0), transforms(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t transforms_lengthT = *(inbuffer + offset++); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped)); + offset += 3; + transforms_length = transforms_lengthT; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped)); + } + return offset; + } + + const char * getType(){ return "tf/tfMessage"; }; + const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/transform_broadcaster.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TRANSFORM_BROADCASTER_H_ +#define ROS_TRANSFORM_BROADCASTER_H_ + +#include "tfMessage.h" + +namespace tf +{ + + class TransformBroadcaster + { + public: + TransformBroadcaster() : publisher_("/tf", &internal_msg) {} + + void init(ros::NodeHandle &nh) + { + nh.advertise(publisher_); + } + + void sendTransform(geometry_msgs::TransformStamped &transform) + { + internal_msg.transforms_length = 1; + internal_msg.transforms = &transform; + publisher_.publish(&internal_msg); + } + + private: + tf::tfMessage internal_msg; + ros::Publisher publisher_; + }; + +} + +#endif + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/FrameGraph.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_FrameGraph_h +#define _ROS_SERVICE_FrameGraph_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace tf2_msgs +{ + +static const char FRAMEGRAPH[] = "tf2_msgs/FrameGraph"; + + class FrameGraphRequest : public ros::Msg + { + public: + + FrameGraphRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class FrameGraphResponse : public ros::Msg + { + public: + const char* frame_yaml; + + FrameGraphResponse(): + frame_yaml("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_frame_yaml = strlen(this->frame_yaml); + memcpy(outbuffer + offset, &length_frame_yaml, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->frame_yaml, length_frame_yaml); + offset += length_frame_yaml; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_frame_yaml; + memcpy(&length_frame_yaml, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_yaml; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_yaml-1]=0; + this->frame_yaml = (char *)(inbuffer + offset-1); + offset += length_frame_yaml; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "437ea58e9463815a0d511c7326b686b0"; }; + + }; + + class FrameGraph { + public: + typedef FrameGraphRequest Request; + typedef FrameGraphResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_tf2_msgs_LookupTransformAction_h +#define _ROS_tf2_msgs_LookupTransformAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "tf2_msgs/LookupTransformActionGoal.h" +#include "tf2_msgs/LookupTransformActionResult.h" +#include "tf2_msgs/LookupTransformActionFeedback.h" + +namespace tf2_msgs +{ + + class LookupTransformAction : public ros::Msg + { + public: + tf2_msgs::LookupTransformActionGoal action_goal; + tf2_msgs::LookupTransformActionResult action_result; + tf2_msgs::LookupTransformActionFeedback action_feedback; + + LookupTransformAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformAction"; }; + const char * getMD5(){ return "7ee01ba91a56c2245c610992dbaa3c37"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_tf2_msgs_LookupTransformActionFeedback_h +#define _ROS_tf2_msgs_LookupTransformActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "tf2_msgs/LookupTransformFeedback.h" + +namespace tf2_msgs +{ + + class LookupTransformActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + tf2_msgs::LookupTransformFeedback feedback; + + LookupTransformActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_tf2_msgs_LookupTransformActionGoal_h +#define _ROS_tf2_msgs_LookupTransformActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "tf2_msgs/LookupTransformGoal.h" + +namespace tf2_msgs +{ + + class LookupTransformActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + tf2_msgs::LookupTransformGoal goal; + + LookupTransformActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformActionGoal"; }; + const char * getMD5(){ return "f2e7bcdb75c847978d0351a13e699da5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_tf2_msgs_LookupTransformActionResult_h +#define _ROS_tf2_msgs_LookupTransformActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "tf2_msgs/LookupTransformResult.h" + +namespace tf2_msgs +{ + + class LookupTransformActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + tf2_msgs::LookupTransformResult result; + + LookupTransformActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformActionResult"; }; + const char * getMD5(){ return "ac26ce75a41384fa8bb4dc10f491ab90"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_tf2_msgs_LookupTransformFeedback_h +#define _ROS_tf2_msgs_LookupTransformFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace tf2_msgs +{ + + class LookupTransformFeedback : public ros::Msg + { + public: + + LookupTransformFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,171 @@ +#ifndef _ROS_tf2_msgs_LookupTransformGoal_h +#define _ROS_tf2_msgs_LookupTransformGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "ros/duration.h" + +namespace tf2_msgs +{ + + class LookupTransformGoal : public ros::Msg + { + public: + const char* target_frame; + const char* source_frame; + ros::Time source_time; + ros::Duration timeout; + ros::Time target_time; + const char* fixed_frame; + bool advanced; + + LookupTransformGoal(): + target_frame(""), + source_frame(""), + source_time(), + timeout(), + target_time(), + fixed_frame(""), + advanced(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_target_frame = strlen(this->target_frame); + memcpy(outbuffer + offset, &length_target_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->target_frame, length_target_frame); + offset += length_target_frame; + uint32_t length_source_frame = strlen(this->source_frame); + memcpy(outbuffer + offset, &length_source_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->source_frame, length_source_frame); + offset += length_source_frame; + *(outbuffer + offset + 0) = (this->source_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->source_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->source_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->source_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->source_time.sec); + *(outbuffer + offset + 0) = (this->source_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->source_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->source_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->source_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->source_time.nsec); + *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.sec); + *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->timeout.nsec); + *(outbuffer + offset + 0) = (this->target_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->target_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->target_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->target_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->target_time.sec); + *(outbuffer + offset + 0) = (this->target_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->target_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->target_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->target_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->target_time.nsec); + uint32_t length_fixed_frame = strlen(this->fixed_frame); + memcpy(outbuffer + offset, &length_fixed_frame, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->fixed_frame, length_fixed_frame); + offset += length_fixed_frame; + union { + bool real; + uint8_t base; + } u_advanced; + u_advanced.real = this->advanced; + *(outbuffer + offset + 0) = (u_advanced.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->advanced); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_target_frame; + memcpy(&length_target_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_target_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_target_frame-1]=0; + this->target_frame = (char *)(inbuffer + offset-1); + offset += length_target_frame; + uint32_t length_source_frame; + memcpy(&length_source_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_source_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_source_frame-1]=0; + this->source_frame = (char *)(inbuffer + offset-1); + offset += length_source_frame; + this->source_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->source_time.sec); + this->source_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->source_time.nsec); + this->timeout.sec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.sec); + this->timeout.nsec = ((uint32_t) (*(inbuffer + offset))); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->timeout.nsec); + this->target_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->target_time.sec); + this->target_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->target_time.nsec); + uint32_t length_fixed_frame; + memcpy(&length_fixed_frame, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_fixed_frame; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_fixed_frame-1]=0; + this->fixed_frame = (char *)(inbuffer + offset-1); + offset += length_fixed_frame; + union { + bool real; + uint8_t base; + } u_advanced; + u_advanced.base = 0; + u_advanced.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->advanced = u_advanced.real; + offset += sizeof(this->advanced); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformGoal"; }; + const char * getMD5(){ return "35e3720468131d675a18bb6f3e5f22f8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/LookupTransformResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,48 @@ +#ifndef _ROS_tf2_msgs_LookupTransformResult_h +#define _ROS_tf2_msgs_LookupTransformResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/TransformStamped.h" +#include "tf2_msgs/TF2Error.h" + +namespace tf2_msgs +{ + + class LookupTransformResult : public ros::Msg + { + public: + geometry_msgs::TransformStamped transform; + tf2_msgs::TF2Error error; + + LookupTransformResult(): + transform(), + error() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->transform.serialize(outbuffer + offset); + offset += this->error.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->transform.deserialize(inbuffer + offset); + offset += this->error.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "tf2_msgs/LookupTransformResult"; }; + const char * getMD5(){ return "3fe5db6a19ca9cfb675418c5ad875c36"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/TF2Error.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_tf2_msgs_TF2Error_h +#define _ROS_tf2_msgs_TF2Error_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace tf2_msgs +{ + + class TF2Error : public ros::Msg + { + public: + uint8_t error; + const char* error_string; + enum { NO_ERROR = 0 }; + enum { LOOKUP_ERROR = 1 }; + enum { CONNECTIVITY_ERROR = 2 }; + enum { EXTRAPOLATION_ERROR = 3 }; + enum { INVALID_ARGUMENT_ERROR = 4 }; + enum { TIMEOUT_ERROR = 5 }; + enum { TRANSFORM_ERROR = 6 }; + + TF2Error(): + error(0), + error_string("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->error >> (8 * 0)) & 0xFF; + offset += sizeof(this->error); + uint32_t length_error_string = strlen(this->error_string); + memcpy(outbuffer + offset, &length_error_string, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->error_string, length_error_string); + offset += length_error_string; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->error = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->error); + uint32_t length_error_string; + memcpy(&length_error_string, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_error_string; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_error_string-1]=0; + this->error_string = (char *)(inbuffer + offset-1); + offset += length_error_string; + return offset; + } + + const char * getType(){ return "tf2_msgs/TF2Error"; }; + const char * getMD5(){ return "bc6848fd6fd750c92e38575618a4917d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf2_msgs/TFMessage.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_tf2_msgs_TFMessage_h +#define _ROS_tf2_msgs_TFMessage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/TransformStamped.h" + +namespace tf2_msgs +{ + + class TFMessage : public ros::Msg + { + public: + uint8_t transforms_length; + geometry_msgs::TransformStamped st_transforms; + geometry_msgs::TransformStamped * transforms; + + TFMessage(): + transforms_length(0), transforms(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t transforms_lengthT = *(inbuffer + offset++); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped)); + offset += 3; + transforms_length = transforms_lengthT; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped)); + } + return offset; + } + + const char * getType(){ return "tf2_msgs/TFMessage"; }; + const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/theora_image_transport/Packet.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,173 @@ +#ifndef _ROS_theora_image_transport_Packet_h +#define _ROS_theora_image_transport_Packet_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace theora_image_transport +{ + + class Packet : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + int32_t b_o_s; + int32_t e_o_s; + int64_t granulepos; + int64_t packetno; + + Packet(): + header(), + data_length(0), data(NULL), + b_o_s(0), + e_o_s(0), + granulepos(0), + packetno(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + union { + int32_t real; + uint32_t base; + } u_b_o_s; + u_b_o_s.real = this->b_o_s; + *(outbuffer + offset + 0) = (u_b_o_s.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b_o_s.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b_o_s.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b_o_s.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b_o_s); + union { + int32_t real; + uint32_t base; + } u_e_o_s; + u_e_o_s.real = this->e_o_s; + *(outbuffer + offset + 0) = (u_e_o_s.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_e_o_s.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_e_o_s.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_e_o_s.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->e_o_s); + union { + int64_t real; + uint64_t base; + } u_granulepos; + u_granulepos.real = this->granulepos; + *(outbuffer + offset + 0) = (u_granulepos.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_granulepos.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_granulepos.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_granulepos.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_granulepos.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_granulepos.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_granulepos.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_granulepos.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->granulepos); + union { + int64_t real; + uint64_t base; + } u_packetno; + u_packetno.real = this->packetno; + *(outbuffer + offset + 0) = (u_packetno.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_packetno.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_packetno.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_packetno.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_packetno.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_packetno.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_packetno.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_packetno.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->packetno); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + union { + int32_t real; + uint32_t base; + } u_b_o_s; + u_b_o_s.base = 0; + u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b_o_s.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b_o_s = u_b_o_s.real; + offset += sizeof(this->b_o_s); + union { + int32_t real; + uint32_t base; + } u_e_o_s; + u_e_o_s.base = 0; + u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_e_o_s.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->e_o_s = u_e_o_s.real; + offset += sizeof(this->e_o_s); + union { + int64_t real; + uint64_t base; + } u_granulepos; + u_granulepos.base = 0; + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_granulepos.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->granulepos = u_granulepos.real; + offset += sizeof(this->granulepos); + union { + int64_t real; + uint64_t base; + } u_packetno; + u_packetno.base = 0; + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_packetno.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->packetno = u_packetno.real; + offset += sizeof(this->packetno); + return offset; + } + + const char * getType(){ return "theora_image_transport/Packet"; }; + const char * getMD5(){ return "33ac4e14a7cff32e7e0d65f18bb410f3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/time.cpp Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,70 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "ros/time.h" + +namespace ros +{ + void normalizeSecNSec(unsigned long& sec, unsigned long& nsec){ + unsigned long nsec_part= nsec % 1000000000UL; + unsigned long sec_part = nsec / 1000000000UL; + sec += sec_part; + nsec = nsec_part; + } + + Time& Time::fromNSec(long t) + { + sec = t / 1000000000; + nsec = t % 1000000000; + normalizeSecNSec(sec, nsec); + return *this; + } + + Time& Time::operator +=(const Duration &rhs) + { + sec += rhs.sec; + nsec += rhs.nsec; + normalizeSecNSec(sec, nsec); + return *this; + } + + Time& Time::operator -=(const Duration &rhs){ + sec += -rhs.sec; + nsec += -rhs.nsec; + normalizeSecNSec(sec, nsec); + return *this; + } + +} +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxAdd.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_MuxAdd_h +#define _ROS_SERVICE_MuxAdd_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXADD[] = "topic_tools/MuxAdd"; + + class MuxAddRequest : public ros::Msg + { + public: + const char* topic; + + MuxAddRequest(): + topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen(this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXADD; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxAddResponse : public ros::Msg + { + public: + + MuxAddResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXADD; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxAdd { + public: + typedef MuxAddRequest Request; + typedef MuxAddResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxDelete.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_MuxDelete_h +#define _ROS_SERVICE_MuxDelete_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXDELETE[] = "topic_tools/MuxDelete"; + + class MuxDeleteRequest : public ros::Msg + { + public: + const char* topic; + + MuxDeleteRequest(): + topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen(this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXDELETE; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxDeleteResponse : public ros::Msg + { + public: + + MuxDeleteResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXDELETE; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxDelete { + public: + typedef MuxDeleteRequest Request; + typedef MuxDeleteResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxList.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_SERVICE_MuxList_h +#define _ROS_SERVICE_MuxList_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXLIST[] = "topic_tools/MuxList"; + + class MuxListRequest : public ros::Msg + { + public: + + MuxListRequest() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXLIST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxListResponse : public ros::Msg + { + public: + uint8_t topics_length; + char* st_topics; + char* * topics; + + MuxListResponse(): + topics_length(0), topics(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = topics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_topicsi = strlen(this->topics[i]); + memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topics[i], length_topicsi); + offset += length_topicsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t topics_lengthT = *(inbuffer + offset++); + if(topics_lengthT > topics_length) + this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); + offset += 3; + topics_length = topics_lengthT; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_st_topics; + memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_topics; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_topics-1]=0; + this->st_topics = (char *)(inbuffer + offset-1); + offset += length_st_topics; + memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return MUXLIST; }; + const char * getMD5(){ return "b0eef9a05d4e829092fc2f2c3c2aad3d"; }; + + }; + + class MuxList { + public: + typedef MuxListRequest Request; + typedef MuxListResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxSelect.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_SERVICE_MuxSelect_h +#define _ROS_SERVICE_MuxSelect_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXSELECT[] = "topic_tools/MuxSelect"; + + class MuxSelectRequest : public ros::Msg + { + public: + const char* topic; + + MuxSelectRequest(): + topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen(this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXSELECT; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxSelectResponse : public ros::Msg + { + public: + const char* prev_topic; + + MuxSelectResponse(): + prev_topic("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_prev_topic = strlen(this->prev_topic); + memcpy(outbuffer + offset, &length_prev_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->prev_topic, length_prev_topic); + offset += length_prev_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_prev_topic; + memcpy(&length_prev_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_prev_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_prev_topic-1]=0; + this->prev_topic = (char *)(inbuffer + offset-1); + offset += length_prev_topic; + return offset; + } + + const char * getType(){ return MUXSELECT; }; + const char * getMD5(){ return "3db0a473debdbafea387c9e49358c320"; }; + + }; + + class MuxSelect { + public: + typedef MuxSelectRequest Request; + typedef MuxSelectResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/trajectory_msgs/JointTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_trajectory_msgs_JointTrajectory_h +#define _ROS_trajectory_msgs_JointTrajectory_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "trajectory_msgs/JointTrajectoryPoint.h" + +namespace trajectory_msgs +{ + + class JointTrajectory : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t points_length; + trajectory_msgs::JointTrajectoryPoint st_points; + trajectory_msgs::JointTrajectoryPoint * points; + + JointTrajectory(): + header(), + joint_names_length(0), joint_names(NULL), + points_length(0), points(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (trajectory_msgs::JointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::JointTrajectoryPoint)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::JointTrajectoryPoint)); + } + return offset; + } + + const char * getType(){ return "trajectory_msgs/JointTrajectory"; }; + const char * getMD5(){ return "65b4f94a94d1ed67169da35a02f33d3f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/trajectory_msgs/JointTrajectoryPoint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,141 @@ +#ifndef _ROS_trajectory_msgs_JointTrajectoryPoint_h +#define _ROS_trajectory_msgs_JointTrajectoryPoint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace trajectory_msgs +{ + + class JointTrajectoryPoint : public ros::Msg + { + public: + uint8_t positions_length; + float st_positions; + float * positions; + uint8_t velocities_length; + float st_velocities; + float * velocities; + uint8_t accelerations_length; + float st_accelerations; + float * accelerations; + uint8_t effort_length; + float st_effort; + float * effort; + ros::Duration time_from_start; + + JointTrajectoryPoint(): + positions_length(0), positions(NULL), + velocities_length(0), velocities(NULL), + accelerations_length(0), accelerations(NULL), + effort_length(0), effort(NULL), + time_from_start() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = positions_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < positions_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->positions[i]); + } + *(outbuffer + offset++) = velocities_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < velocities_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->velocities[i]); + } + *(outbuffer + offset++) = accelerations_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < accelerations_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->accelerations[i]); + } + *(outbuffer + offset++) = effort_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < effort_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->effort[i]); + } + *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_from_start.sec); + *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_from_start.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t positions_lengthT = *(inbuffer + offset++); + if(positions_lengthT > positions_length) + this->positions = (float*)realloc(this->positions, positions_lengthT * sizeof(float)); + offset += 3; + positions_length = positions_lengthT; + for( uint8_t i = 0; i < positions_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_positions)); + memcpy( &(this->positions[i]), &(this->st_positions), sizeof(float)); + } + uint8_t velocities_lengthT = *(inbuffer + offset++); + if(velocities_lengthT > velocities_length) + this->velocities = (float*)realloc(this->velocities, velocities_lengthT * sizeof(float)); + offset += 3; + velocities_length = velocities_lengthT; + for( uint8_t i = 0; i < velocities_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_velocities)); + memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(float)); + } + uint8_t accelerations_lengthT = *(inbuffer + offset++); + if(accelerations_lengthT > accelerations_length) + this->accelerations = (float*)realloc(this->accelerations, accelerations_lengthT * sizeof(float)); + offset += 3; + accelerations_length = accelerations_lengthT; + for( uint8_t i = 0; i < accelerations_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_accelerations)); + memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(float)); + } + uint8_t effort_lengthT = *(inbuffer + offset++); + if(effort_lengthT > effort_length) + this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float)); + offset += 3; + effort_length = effort_lengthT; + for( uint8_t i = 0; i < effort_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_effort)); + memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float)); + } + this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset))); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_from_start.sec); + this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_from_start.nsec); + return offset; + } + + const char * getType(){ return "trajectory_msgs/JointTrajectoryPoint"; }; + const char * getMD5(){ return "f3cd1e1c4d320c79d6985c904ae5dcd3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/trajectory_msgs/MultiDOFJointTrajectory.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectory_h +#define _ROS_trajectory_msgs_MultiDOFJointTrajectory_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "trajectory_msgs/MultiDOFJointTrajectoryPoint.h" + +namespace trajectory_msgs +{ + + class MultiDOFJointTrajectory : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t joint_names_length; + char* st_joint_names; + char* * joint_names; + uint8_t points_length; + trajectory_msgs::MultiDOFJointTrajectoryPoint st_points; + trajectory_msgs::MultiDOFJointTrajectoryPoint * points; + + MultiDOFJointTrajectory(): + header(), + joint_names_length(0), joint_names(NULL), + points_length(0), points(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = joint_names_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_joint_namesi = strlen(this->joint_names[i]); + memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); + offset += length_joint_namesi; + } + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t joint_names_lengthT = *(inbuffer + offset++); + if(joint_names_lengthT > joint_names_length) + this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); + offset += 3; + joint_names_length = joint_names_lengthT; + for( uint8_t i = 0; i < joint_names_length; i++){ + uint32_t length_st_joint_names; + memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_joint_names-1]=0; + this->st_joint_names = (char *)(inbuffer + offset-1); + offset += length_st_joint_names; + memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); + } + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (trajectory_msgs::MultiDOFJointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint)); + } + return offset; + } + + const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectory"; }; + const char * getMD5(){ return "ef145a45a5f47b77b7f5cdde4b16c942"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/trajectory_msgs/MultiDOFJointTrajectoryPoint.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,123 @@ +#ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h +#define _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Transform.h" +#include "geometry_msgs/Twist.h" +#include "ros/duration.h" + +namespace trajectory_msgs +{ + + class MultiDOFJointTrajectoryPoint : public ros::Msg + { + public: + uint8_t transforms_length; + geometry_msgs::Transform st_transforms; + geometry_msgs::Transform * transforms; + uint8_t velocities_length; + geometry_msgs::Twist st_velocities; + geometry_msgs::Twist * velocities; + uint8_t accelerations_length; + geometry_msgs::Twist st_accelerations; + geometry_msgs::Twist * accelerations; + ros::Duration time_from_start; + + MultiDOFJointTrajectoryPoint(): + transforms_length(0), transforms(NULL), + velocities_length(0), velocities(NULL), + accelerations_length(0), accelerations(NULL), + time_from_start() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = velocities_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < velocities_length; i++){ + offset += this->velocities[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = accelerations_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < accelerations_length; i++){ + offset += this->accelerations[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_from_start.sec); + *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_from_start.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t transforms_lengthT = *(inbuffer + offset++); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform)); + offset += 3; + transforms_length = transforms_lengthT; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform)); + } + uint8_t velocities_lengthT = *(inbuffer + offset++); + if(velocities_lengthT > velocities_length) + this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + velocities_length = velocities_lengthT; + for( uint8_t i = 0; i < velocities_length; i++){ + offset += this->st_velocities.deserialize(inbuffer + offset); + memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist)); + } + uint8_t accelerations_lengthT = *(inbuffer + offset++); + if(accelerations_lengthT > accelerations_length) + this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist)); + offset += 3; + accelerations_length = accelerations_lengthT; + for( uint8_t i = 0; i < accelerations_length; i++){ + offset += this->st_accelerations.deserialize(inbuffer + offset); + memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist)); + } + this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset))); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_from_start.sec); + this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset))); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->time_from_start.nsec); + return offset; + } + + const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; }; + const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeAction.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_turtle_actionlib_ShapeAction_h +#define _ROS_turtle_actionlib_ShapeAction_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "turtle_actionlib/ShapeActionGoal.h" +#include "turtle_actionlib/ShapeActionResult.h" +#include "turtle_actionlib/ShapeActionFeedback.h" + +namespace turtle_actionlib +{ + + class ShapeAction : public ros::Msg + { + public: + turtle_actionlib::ShapeActionGoal action_goal; + turtle_actionlib::ShapeActionResult action_result; + turtle_actionlib::ShapeActionFeedback action_feedback; + + ShapeAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->action_goal.serialize(outbuffer + offset); + offset += this->action_result.serialize(outbuffer + offset); + offset += this->action_feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->action_goal.deserialize(inbuffer + offset); + offset += this->action_result.deserialize(inbuffer + offset); + offset += this->action_feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeAction"; }; + const char * getMD5(){ return "d73b17d6237a925511f5d7727a1dc903"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeActionFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_turtle_actionlib_ShapeActionFeedback_h +#define _ROS_turtle_actionlib_ShapeActionFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "turtle_actionlib/ShapeFeedback.h" + +namespace turtle_actionlib +{ + + class ShapeActionFeedback : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + turtle_actionlib::ShapeFeedback feedback; + + ShapeActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->feedback.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeActionFeedback"; }; + const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeActionGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_turtle_actionlib_ShapeActionGoal_h +#define _ROS_turtle_actionlib_ShapeActionGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "turtle_actionlib/ShapeGoal.h" + +namespace turtle_actionlib +{ + + class ShapeActionGoal : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalID goal_id; + turtle_actionlib::ShapeGoal goal; + + ShapeActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->goal_id.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeActionGoal"; }; + const char * getMD5(){ return "dbfccd187f2ec9c593916447ffd6cc77"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeActionResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,53 @@ +#ifndef _ROS_turtle_actionlib_ShapeActionResult_h +#define _ROS_turtle_actionlib_ShapeActionResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "turtle_actionlib/ShapeResult.h" + +namespace turtle_actionlib +{ + + class ShapeActionResult : public ros::Msg + { + public: + std_msgs::Header header; + actionlib_msgs::GoalStatus status; + turtle_actionlib::ShapeResult result; + + ShapeActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + offset += this->result.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeActionResult"; }; + const char * getMD5(){ return "c8d13d5d140f1047a2e4d3bf5c045822"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,38 @@ +#ifndef _ROS_turtle_actionlib_ShapeFeedback_h +#define _ROS_turtle_actionlib_ShapeFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtle_actionlib +{ + + class ShapeFeedback : public ros::Msg + { + public: + + ShapeFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeFeedback"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeGoal.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_turtle_actionlib_ShapeGoal_h +#define _ROS_turtle_actionlib_ShapeGoal_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtle_actionlib +{ + + class ShapeGoal : public ros::Msg + { + public: + int32_t edges; + float radius; + + ShapeGoal(): + edges(0), + radius(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_edges; + u_edges.real = this->edges; + *(outbuffer + offset + 0) = (u_edges.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_edges.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_edges.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_edges.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->edges); + union { + float real; + uint32_t base; + } u_radius; + u_radius.real = this->radius; + *(outbuffer + offset + 0) = (u_radius.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_radius.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_radius.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_radius.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->radius); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_edges; + u_edges.base = 0; + u_edges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_edges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_edges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_edges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->edges = u_edges.real; + offset += sizeof(this->edges); + union { + float real; + uint32_t base; + } u_radius; + u_radius.base = 0; + u_radius.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_radius.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_radius.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_radius.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->radius = u_radius.real; + offset += sizeof(this->radius); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeGoal"; }; + const char * getMD5(){ return "3b9202ab7292cebe5a95ab2bf6b9c091"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/ShapeResult.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_turtle_actionlib_ShapeResult_h +#define _ROS_turtle_actionlib_ShapeResult_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtle_actionlib +{ + + class ShapeResult : public ros::Msg + { + public: + float interior_angle; + float apothem; + + ShapeResult(): + interior_angle(0), + apothem(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_interior_angle; + u_interior_angle.real = this->interior_angle; + *(outbuffer + offset + 0) = (u_interior_angle.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_interior_angle.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_interior_angle.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_interior_angle.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->interior_angle); + union { + float real; + uint32_t base; + } u_apothem; + u_apothem.real = this->apothem; + *(outbuffer + offset + 0) = (u_apothem.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_apothem.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_apothem.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_apothem.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->apothem); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_interior_angle; + u_interior_angle.base = 0; + u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_interior_angle.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->interior_angle = u_interior_angle.real; + offset += sizeof(this->interior_angle); + union { + float real; + uint32_t base; + } u_apothem; + u_apothem.base = 0; + u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_apothem.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->apothem = u_apothem.real; + offset += sizeof(this->apothem); + return offset; + } + + const char * getType(){ return "turtle_actionlib/ShapeResult"; }; + const char * getMD5(){ return "b06c6e2225f820dbc644270387cd1a7c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtle_actionlib/Velocity.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_turtle_actionlib_Velocity_h +#define _ROS_turtle_actionlib_Velocity_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtle_actionlib +{ + + class Velocity : public ros::Msg + { + public: + float linear; + float angular; + + Velocity(): + linear(0), + angular(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_linear; + u_linear.real = this->linear; + *(outbuffer + offset + 0) = (u_linear.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_linear.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_linear.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_linear.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->linear); + union { + float real; + uint32_t base; + } u_angular; + u_angular.real = this->angular; + *(outbuffer + offset + 0) = (u_angular.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angular.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angular.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angular.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angular); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_linear; + u_linear.base = 0; + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->linear = u_linear.real; + offset += sizeof(this->linear); + union { + float real; + uint32_t base; + } u_angular; + u_angular.base = 0; + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angular = u_angular.real; + offset += sizeof(this->angular); + return offset; + } + + const char * getType(){ return "turtle_actionlib/Velocity"; }; + const char * getMD5(){ return "9d5c2dcd348ac8f76ce2a4307bd63a13"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/Color.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_turtlesim_Color_h +#define _ROS_turtlesim_Color_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + + class Color : public ros::Msg + { + public: + uint8_t r; + uint8_t g; + uint8_t b; + + Color(): + r(0), + g(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF; + offset += sizeof(this->r); + *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF; + offset += sizeof(this->g); + *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF; + offset += sizeof(this->b); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->r = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->r); + this->g = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->g); + this->b = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->b); + return offset; + } + + const char * getType(){ return "turtlesim/Color"; }; + const char * getMD5(){ return "353891e354491c51aabe32df673fb446"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/Kill.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_SERVICE_Kill_h +#define _ROS_SERVICE_Kill_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + +static const char KILL[] = "turtlesim/Kill"; + + class KillRequest : public ros::Msg + { + public: + const char* name; + + KillRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return KILL; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class KillResponse : public ros::Msg + { + public: + + KillResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return KILL; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class Kill { + public: + typedef KillRequest Request; + typedef KillResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/Pose.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,153 @@ +#ifndef _ROS_turtlesim_Pose_h +#define _ROS_turtlesim_Pose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + + class Pose : public ros::Msg + { + public: + float x; + float y; + float theta; + float linear_velocity; + float angular_velocity; + + Pose(): + x(0), + y(0), + theta(0), + linear_velocity(0), + angular_velocity(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.real = this->theta; + *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->theta); + union { + float real; + uint32_t base; + } u_linear_velocity; + u_linear_velocity.real = this->linear_velocity; + *(outbuffer + offset + 0) = (u_linear_velocity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_linear_velocity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_linear_velocity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_linear_velocity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->linear_velocity); + union { + float real; + uint32_t base; + } u_angular_velocity; + u_angular_velocity.real = this->angular_velocity; + *(outbuffer + offset + 0) = (u_angular_velocity.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angular_velocity.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angular_velocity.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angular_velocity.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angular_velocity); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.base = 0; + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->theta = u_theta.real; + offset += sizeof(this->theta); + union { + float real; + uint32_t base; + } u_linear_velocity; + u_linear_velocity.base = 0; + u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->linear_velocity = u_linear_velocity.real; + offset += sizeof(this->linear_velocity); + union { + float real; + uint32_t base; + } u_angular_velocity; + u_angular_velocity.base = 0; + u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angular_velocity = u_angular_velocity.real; + offset += sizeof(this->angular_velocity); + return offset; + } + + const char * getType(){ return "turtlesim/Pose"; }; + const char * getMD5(){ return "863b248d5016ca62ea2e895ae5265cf9"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/SetPen.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,101 @@ +#ifndef _ROS_SERVICE_SetPen_h +#define _ROS_SERVICE_SetPen_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + +static const char SETPEN[] = "turtlesim/SetPen"; + + class SetPenRequest : public ros::Msg + { + public: + uint8_t r; + uint8_t g; + uint8_t b; + uint8_t width; + uint8_t off; + + SetPenRequest(): + r(0), + g(0), + b(0), + width(0), + off(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF; + offset += sizeof(this->r); + *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF; + offset += sizeof(this->g); + *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF; + offset += sizeof(this->b); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset + 0) = (this->off >> (8 * 0)) & 0xFF; + offset += sizeof(this->off); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->r = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->r); + this->g = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->g); + this->b = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->b); + this->width = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->width); + this->off = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->off); + return offset; + } + + const char * getType(){ return SETPEN; }; + const char * getMD5(){ return "9f452acce566bf0c0954594f69a8e41b"; }; + + }; + + class SetPenResponse : public ros::Msg + { + public: + + SetPenResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SETPEN; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetPen { + public: + typedef SetPenRequest Request; + typedef SetPenResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/Spawn.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,172 @@ +#ifndef _ROS_SERVICE_Spawn_h +#define _ROS_SERVICE_Spawn_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + +static const char SPAWN[] = "turtlesim/Spawn"; + + class SpawnRequest : public ros::Msg + { + public: + float x; + float y; + float theta; + const char* name; + + SpawnRequest(): + x(0), + y(0), + theta(0), + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.real = this->theta; + *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->theta); + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.base = 0; + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->theta = u_theta.real; + offset += sizeof(this->theta); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return SPAWN; }; + const char * getMD5(){ return "57f001c49ab7b11d699f8606c1f4f7ff"; }; + + }; + + class SpawnResponse : public ros::Msg + { + public: + const char* name; + + SpawnResponse(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return SPAWN; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class Spawn { + public: + typedef SpawnRequest Request; + typedef SpawnResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/TeleportAbsolute.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,140 @@ +#ifndef _ROS_SERVICE_TeleportAbsolute_h +#define _ROS_SERVICE_TeleportAbsolute_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + +static const char TELEPORTABSOLUTE[] = "turtlesim/TeleportAbsolute"; + + class TeleportAbsoluteRequest : public ros::Msg + { + public: + float x; + float y; + float theta; + + TeleportAbsoluteRequest(): + x(0), + y(0), + theta(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.real = this->theta; + *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->theta); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_theta; + u_theta.base = 0; + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->theta = u_theta.real; + offset += sizeof(this->theta); + return offset; + } + + const char * getType(){ return TELEPORTABSOLUTE; }; + const char * getMD5(){ return "a130bc60ee6513855dc62ea83fcc5b20"; }; + + }; + + class TeleportAbsoluteResponse : public ros::Msg + { + public: + + TeleportAbsoluteResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return TELEPORTABSOLUTE; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class TeleportAbsolute { + public: + typedef TeleportAbsoluteRequest Request; + typedef TeleportAbsoluteResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/turtlesim/TeleportRelative.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,117 @@ +#ifndef _ROS_SERVICE_TeleportRelative_h +#define _ROS_SERVICE_TeleportRelative_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace turtlesim +{ + +static const char TELEPORTRELATIVE[] = "turtlesim/TeleportRelative"; + + class TeleportRelativeRequest : public ros::Msg + { + public: + float linear; + float angular; + + TeleportRelativeRequest(): + linear(0), + angular(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_linear; + u_linear.real = this->linear; + *(outbuffer + offset + 0) = (u_linear.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_linear.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_linear.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_linear.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->linear); + union { + float real; + uint32_t base; + } u_angular; + u_angular.real = this->angular; + *(outbuffer + offset + 0) = (u_angular.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angular.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angular.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angular.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angular); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_linear; + u_linear.base = 0; + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_linear.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->linear = u_linear.real; + offset += sizeof(this->linear); + union { + float real; + uint32_t base; + } u_angular; + u_angular.base = 0; + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angular.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angular = u_angular.real; + offset += sizeof(this->angular); + return offset; + } + + const char * getType(){ return TELEPORTRELATIVE; }; + const char * getMD5(){ return "9d5c2dcd348ac8f76ce2a4307bd63a13"; }; + + }; + + class TeleportRelativeResponse : public ros::Msg + { + public: + + TeleportRelativeResponse() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return TELEPORTRELATIVE; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class TeleportRelative { + public: + typedef TeleportRelativeRequest Request; + typedef TeleportRelativeResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/Analog.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_ur_msgs_Analog_h +#define _ROS_ur_msgs_Analog_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + + class Analog : public ros::Msg + { + public: + uint8_t pin; + float state; + + Analog(): + pin(0), + state(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->pin >> (8 * 0)) & 0xFF; + offset += sizeof(this->pin); + union { + float real; + uint32_t base; + } u_state; + u_state.real = this->state; + *(outbuffer + offset + 0) = (u_state.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_state.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_state.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_state.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->state); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->pin = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->pin); + union { + float real; + uint32_t base; + } u_state; + u_state.base = 0; + u_state.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->state = u_state.real; + offset += sizeof(this->state); + return offset; + } + + const char * getType(){ return "ur_msgs/Analog"; }; + const char * getMD5(){ return "341541c8828d055b6dcc443d40207a7d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/Digital.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_ur_msgs_Digital_h +#define _ROS_ur_msgs_Digital_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + + class Digital : public ros::Msg + { + public: + uint8_t pin; + bool state; + + Digital(): + pin(0), + state(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->pin >> (8 * 0)) & 0xFF; + offset += sizeof(this->pin); + union { + bool real; + uint8_t base; + } u_state; + u_state.real = this->state; + *(outbuffer + offset + 0) = (u_state.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->state); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->pin = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->pin); + union { + bool real; + uint8_t base; + } u_state; + u_state.base = 0; + u_state.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->state = u_state.real; + offset += sizeof(this->state); + return offset; + } + + const char * getType(){ return "ur_msgs/Digital"; }; + const char * getMD5(){ return "83707be3fa18d2ffe57381ea034aa262"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/IOStates.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,140 @@ +#ifndef _ROS_ur_msgs_IOStates_h +#define _ROS_ur_msgs_IOStates_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ur_msgs/Digital.h" +#include "ur_msgs/Analog.h" + +namespace ur_msgs +{ + + class IOStates : public ros::Msg + { + public: + uint8_t digital_in_states_length; + ur_msgs::Digital st_digital_in_states; + ur_msgs::Digital * digital_in_states; + uint8_t digital_out_states_length; + ur_msgs::Digital st_digital_out_states; + ur_msgs::Digital * digital_out_states; + uint8_t flag_states_length; + ur_msgs::Digital st_flag_states; + ur_msgs::Digital * flag_states; + uint8_t analog_in_states_length; + ur_msgs::Analog st_analog_in_states; + ur_msgs::Analog * analog_in_states; + uint8_t analog_out_states_length; + ur_msgs::Analog st_analog_out_states; + ur_msgs::Analog * analog_out_states; + + IOStates(): + digital_in_states_length(0), digital_in_states(NULL), + digital_out_states_length(0), digital_out_states(NULL), + flag_states_length(0), flag_states(NULL), + analog_in_states_length(0), analog_in_states(NULL), + analog_out_states_length(0), analog_out_states(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = digital_in_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < digital_in_states_length; i++){ + offset += this->digital_in_states[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = digital_out_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < digital_out_states_length; i++){ + offset += this->digital_out_states[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = flag_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < flag_states_length; i++){ + offset += this->flag_states[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = analog_in_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < analog_in_states_length; i++){ + offset += this->analog_in_states[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = analog_out_states_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < analog_out_states_length; i++){ + offset += this->analog_out_states[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t digital_in_states_lengthT = *(inbuffer + offset++); + if(digital_in_states_lengthT > digital_in_states_length) + this->digital_in_states = (ur_msgs::Digital*)realloc(this->digital_in_states, digital_in_states_lengthT * sizeof(ur_msgs::Digital)); + offset += 3; + digital_in_states_length = digital_in_states_lengthT; + for( uint8_t i = 0; i < digital_in_states_length; i++){ + offset += this->st_digital_in_states.deserialize(inbuffer + offset); + memcpy( &(this->digital_in_states[i]), &(this->st_digital_in_states), sizeof(ur_msgs::Digital)); + } + uint8_t digital_out_states_lengthT = *(inbuffer + offset++); + if(digital_out_states_lengthT > digital_out_states_length) + this->digital_out_states = (ur_msgs::Digital*)realloc(this->digital_out_states, digital_out_states_lengthT * sizeof(ur_msgs::Digital)); + offset += 3; + digital_out_states_length = digital_out_states_lengthT; + for( uint8_t i = 0; i < digital_out_states_length; i++){ + offset += this->st_digital_out_states.deserialize(inbuffer + offset); + memcpy( &(this->digital_out_states[i]), &(this->st_digital_out_states), sizeof(ur_msgs::Digital)); + } + uint8_t flag_states_lengthT = *(inbuffer + offset++); + if(flag_states_lengthT > flag_states_length) + this->flag_states = (ur_msgs::Digital*)realloc(this->flag_states, flag_states_lengthT * sizeof(ur_msgs::Digital)); + offset += 3; + flag_states_length = flag_states_lengthT; + for( uint8_t i = 0; i < flag_states_length; i++){ + offset += this->st_flag_states.deserialize(inbuffer + offset); + memcpy( &(this->flag_states[i]), &(this->st_flag_states), sizeof(ur_msgs::Digital)); + } + uint8_t analog_in_states_lengthT = *(inbuffer + offset++); + if(analog_in_states_lengthT > analog_in_states_length) + this->analog_in_states = (ur_msgs::Analog*)realloc(this->analog_in_states, analog_in_states_lengthT * sizeof(ur_msgs::Analog)); + offset += 3; + analog_in_states_length = analog_in_states_lengthT; + for( uint8_t i = 0; i < analog_in_states_length; i++){ + offset += this->st_analog_in_states.deserialize(inbuffer + offset); + memcpy( &(this->analog_in_states[i]), &(this->st_analog_in_states), sizeof(ur_msgs::Analog)); + } + uint8_t analog_out_states_lengthT = *(inbuffer + offset++); + if(analog_out_states_lengthT > analog_out_states_length) + this->analog_out_states = (ur_msgs::Analog*)realloc(this->analog_out_states, analog_out_states_lengthT * sizeof(ur_msgs::Analog)); + offset += 3; + analog_out_states_length = analog_out_states_lengthT; + for( uint8_t i = 0; i < analog_out_states_length; i++){ + offset += this->st_analog_out_states.deserialize(inbuffer + offset); + memcpy( &(this->analog_out_states[i]), &(this->st_analog_out_states), sizeof(ur_msgs::Analog)); + } + return offset; + } + + const char * getType(){ return "ur_msgs/IOStates"; }; + const char * getMD5(){ return "0a5c7b73e3189e9a2caf8583d1bae2e2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/MasterboardDataMsg.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,264 @@ +#ifndef _ROS_ur_msgs_MasterboardDataMsg_h +#define _ROS_ur_msgs_MasterboardDataMsg_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + + class MasterboardDataMsg : public ros::Msg + { + public: + int16_t digital_input_bits; + int16_t digital_output_bits; + int8_t analog_input_range0; + int8_t analog_input_range1; + float analog_input0; + float analog_input1; + int8_t analog_output_domain0; + int8_t analog_output_domain1; + float analog_output0; + float analog_output1; + float masterboard_temperature; + float robot_voltage_48V; + float robot_current; + float master_io_current; + uint8_t master_safety_state; + uint8_t master_onoff_state; + + MasterboardDataMsg(): + digital_input_bits(0), + digital_output_bits(0), + analog_input_range0(0), + analog_input_range1(0), + analog_input0(0), + analog_input1(0), + analog_output_domain0(0), + analog_output_domain1(0), + analog_output0(0), + analog_output1(0), + masterboard_temperature(0), + robot_voltage_48V(0), + robot_current(0), + master_io_current(0), + master_safety_state(0), + master_onoff_state(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_digital_input_bits; + u_digital_input_bits.real = this->digital_input_bits; + *(outbuffer + offset + 0) = (u_digital_input_bits.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_digital_input_bits.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->digital_input_bits); + union { + int16_t real; + uint16_t base; + } u_digital_output_bits; + u_digital_output_bits.real = this->digital_output_bits; + *(outbuffer + offset + 0) = (u_digital_output_bits.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_digital_output_bits.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->digital_output_bits); + union { + int8_t real; + uint8_t base; + } u_analog_input_range0; + u_analog_input_range0.real = this->analog_input_range0; + *(outbuffer + offset + 0) = (u_analog_input_range0.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->analog_input_range0); + union { + int8_t real; + uint8_t base; + } u_analog_input_range1; + u_analog_input_range1.real = this->analog_input_range1; + *(outbuffer + offset + 0) = (u_analog_input_range1.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->analog_input_range1); + offset += serializeAvrFloat64(outbuffer + offset, this->analog_input0); + offset += serializeAvrFloat64(outbuffer + offset, this->analog_input1); + union { + int8_t real; + uint8_t base; + } u_analog_output_domain0; + u_analog_output_domain0.real = this->analog_output_domain0; + *(outbuffer + offset + 0) = (u_analog_output_domain0.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->analog_output_domain0); + union { + int8_t real; + uint8_t base; + } u_analog_output_domain1; + u_analog_output_domain1.real = this->analog_output_domain1; + *(outbuffer + offset + 0) = (u_analog_output_domain1.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->analog_output_domain1); + offset += serializeAvrFloat64(outbuffer + offset, this->analog_output0); + offset += serializeAvrFloat64(outbuffer + offset, this->analog_output1); + union { + float real; + uint32_t base; + } u_masterboard_temperature; + u_masterboard_temperature.real = this->masterboard_temperature; + *(outbuffer + offset + 0) = (u_masterboard_temperature.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_masterboard_temperature.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_masterboard_temperature.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_masterboard_temperature.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->masterboard_temperature); + union { + float real; + uint32_t base; + } u_robot_voltage_48V; + u_robot_voltage_48V.real = this->robot_voltage_48V; + *(outbuffer + offset + 0) = (u_robot_voltage_48V.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_robot_voltage_48V.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_robot_voltage_48V.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_robot_voltage_48V.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->robot_voltage_48V); + union { + float real; + uint32_t base; + } u_robot_current; + u_robot_current.real = this->robot_current; + *(outbuffer + offset + 0) = (u_robot_current.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_robot_current.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_robot_current.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_robot_current.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->robot_current); + union { + float real; + uint32_t base; + } u_master_io_current; + u_master_io_current.real = this->master_io_current; + *(outbuffer + offset + 0) = (u_master_io_current.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_master_io_current.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_master_io_current.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_master_io_current.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->master_io_current); + *(outbuffer + offset + 0) = (this->master_safety_state >> (8 * 0)) & 0xFF; + offset += sizeof(this->master_safety_state); + *(outbuffer + offset + 0) = (this->master_onoff_state >> (8 * 0)) & 0xFF; + offset += sizeof(this->master_onoff_state); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_digital_input_bits; + u_digital_input_bits.base = 0; + u_digital_input_bits.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_digital_input_bits.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->digital_input_bits = u_digital_input_bits.real; + offset += sizeof(this->digital_input_bits); + union { + int16_t real; + uint16_t base; + } u_digital_output_bits; + u_digital_output_bits.base = 0; + u_digital_output_bits.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_digital_output_bits.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->digital_output_bits = u_digital_output_bits.real; + offset += sizeof(this->digital_output_bits); + union { + int8_t real; + uint8_t base; + } u_analog_input_range0; + u_analog_input_range0.base = 0; + u_analog_input_range0.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->analog_input_range0 = u_analog_input_range0.real; + offset += sizeof(this->analog_input_range0); + union { + int8_t real; + uint8_t base; + } u_analog_input_range1; + u_analog_input_range1.base = 0; + u_analog_input_range1.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->analog_input_range1 = u_analog_input_range1.real; + offset += sizeof(this->analog_input_range1); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->analog_input0)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->analog_input1)); + union { + int8_t real; + uint8_t base; + } u_analog_output_domain0; + u_analog_output_domain0.base = 0; + u_analog_output_domain0.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->analog_output_domain0 = u_analog_output_domain0.real; + offset += sizeof(this->analog_output_domain0); + union { + int8_t real; + uint8_t base; + } u_analog_output_domain1; + u_analog_output_domain1.base = 0; + u_analog_output_domain1.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->analog_output_domain1 = u_analog_output_domain1.real; + offset += sizeof(this->analog_output_domain1); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->analog_output0)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->analog_output1)); + union { + float real; + uint32_t base; + } u_masterboard_temperature; + u_masterboard_temperature.base = 0; + u_masterboard_temperature.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_masterboard_temperature.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_masterboard_temperature.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_masterboard_temperature.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->masterboard_temperature = u_masterboard_temperature.real; + offset += sizeof(this->masterboard_temperature); + union { + float real; + uint32_t base; + } u_robot_voltage_48V; + u_robot_voltage_48V.base = 0; + u_robot_voltage_48V.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_robot_voltage_48V.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_robot_voltage_48V.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_robot_voltage_48V.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->robot_voltage_48V = u_robot_voltage_48V.real; + offset += sizeof(this->robot_voltage_48V); + union { + float real; + uint32_t base; + } u_robot_current; + u_robot_current.base = 0; + u_robot_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_robot_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_robot_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_robot_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->robot_current = u_robot_current.real; + offset += sizeof(this->robot_current); + union { + float real; + uint32_t base; + } u_master_io_current; + u_master_io_current.base = 0; + u_master_io_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_master_io_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_master_io_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_master_io_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->master_io_current = u_master_io_current.real; + offset += sizeof(this->master_io_current); + this->master_safety_state = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->master_safety_state); + this->master_onoff_state = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->master_onoff_state); + return offset; + } + + const char * getType(){ return "ur_msgs/MasterboardDataMsg"; }; + const char * getMD5(){ return "a4aa4d8ccbd10a18ef4008b679f6ccbe"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/RobotStateRTMsg.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,338 @@ +#ifndef _ROS_ur_msgs_RobotStateRTMsg_h +#define _ROS_ur_msgs_RobotStateRTMsg_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + + class RobotStateRTMsg : public ros::Msg + { + public: + float time; + uint8_t q_target_length; + float st_q_target; + float * q_target; + uint8_t qd_target_length; + float st_qd_target; + float * qd_target; + uint8_t qdd_target_length; + float st_qdd_target; + float * qdd_target; + uint8_t i_target_length; + float st_i_target; + float * i_target; + uint8_t m_target_length; + float st_m_target; + float * m_target; + uint8_t q_actual_length; + float st_q_actual; + float * q_actual; + uint8_t qd_actual_length; + float st_qd_actual; + float * qd_actual; + uint8_t i_actual_length; + float st_i_actual; + float * i_actual; + uint8_t tool_acc_values_length; + float st_tool_acc_values; + float * tool_acc_values; + uint8_t tcp_force_length; + float st_tcp_force; + float * tcp_force; + uint8_t tool_vector_length; + float st_tool_vector; + float * tool_vector; + uint8_t tcp_speed_length; + float st_tcp_speed; + float * tcp_speed; + float digital_input_bits; + uint8_t motor_temperatures_length; + float st_motor_temperatures; + float * motor_temperatures; + float controller_timer; + float test_value; + float robot_mode; + uint8_t joint_modes_length; + float st_joint_modes; + float * joint_modes; + + RobotStateRTMsg(): + time(0), + q_target_length(0), q_target(NULL), + qd_target_length(0), qd_target(NULL), + qdd_target_length(0), qdd_target(NULL), + i_target_length(0), i_target(NULL), + m_target_length(0), m_target(NULL), + q_actual_length(0), q_actual(NULL), + qd_actual_length(0), qd_actual(NULL), + i_actual_length(0), i_actual(NULL), + tool_acc_values_length(0), tool_acc_values(NULL), + tcp_force_length(0), tcp_force(NULL), + tool_vector_length(0), tool_vector(NULL), + tcp_speed_length(0), tcp_speed(NULL), + digital_input_bits(0), + motor_temperatures_length(0), motor_temperatures(NULL), + controller_timer(0), + test_value(0), + robot_mode(0), + joint_modes_length(0), joint_modes(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += serializeAvrFloat64(outbuffer + offset, this->time); + *(outbuffer + offset++) = q_target_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < q_target_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->q_target[i]); + } + *(outbuffer + offset++) = qd_target_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < qd_target_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->qd_target[i]); + } + *(outbuffer + offset++) = qdd_target_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < qdd_target_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->qdd_target[i]); + } + *(outbuffer + offset++) = i_target_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < i_target_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->i_target[i]); + } + *(outbuffer + offset++) = m_target_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < m_target_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->m_target[i]); + } + *(outbuffer + offset++) = q_actual_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < q_actual_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->q_actual[i]); + } + *(outbuffer + offset++) = qd_actual_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < qd_actual_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->qd_actual[i]); + } + *(outbuffer + offset++) = i_actual_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < i_actual_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->i_actual[i]); + } + *(outbuffer + offset++) = tool_acc_values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tool_acc_values_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->tool_acc_values[i]); + } + *(outbuffer + offset++) = tcp_force_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tcp_force_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->tcp_force[i]); + } + *(outbuffer + offset++) = tool_vector_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tool_vector_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->tool_vector[i]); + } + *(outbuffer + offset++) = tcp_speed_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < tcp_speed_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->tcp_speed[i]); + } + offset += serializeAvrFloat64(outbuffer + offset, this->digital_input_bits); + *(outbuffer + offset++) = motor_temperatures_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < motor_temperatures_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->motor_temperatures[i]); + } + offset += serializeAvrFloat64(outbuffer + offset, this->controller_timer); + offset += serializeAvrFloat64(outbuffer + offset, this->test_value); + offset += serializeAvrFloat64(outbuffer + offset, this->robot_mode); + *(outbuffer + offset++) = joint_modes_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < joint_modes_length; i++){ + offset += serializeAvrFloat64(outbuffer + offset, this->joint_modes[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += deserializeAvrFloat64(inbuffer + offset, &(this->time)); + uint8_t q_target_lengthT = *(inbuffer + offset++); + if(q_target_lengthT > q_target_length) + this->q_target = (float*)realloc(this->q_target, q_target_lengthT * sizeof(float)); + offset += 3; + q_target_length = q_target_lengthT; + for( uint8_t i = 0; i < q_target_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_q_target)); + memcpy( &(this->q_target[i]), &(this->st_q_target), sizeof(float)); + } + uint8_t qd_target_lengthT = *(inbuffer + offset++); + if(qd_target_lengthT > qd_target_length) + this->qd_target = (float*)realloc(this->qd_target, qd_target_lengthT * sizeof(float)); + offset += 3; + qd_target_length = qd_target_lengthT; + for( uint8_t i = 0; i < qd_target_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qd_target)); + memcpy( &(this->qd_target[i]), &(this->st_qd_target), sizeof(float)); + } + uint8_t qdd_target_lengthT = *(inbuffer + offset++); + if(qdd_target_lengthT > qdd_target_length) + this->qdd_target = (float*)realloc(this->qdd_target, qdd_target_lengthT * sizeof(float)); + offset += 3; + qdd_target_length = qdd_target_lengthT; + for( uint8_t i = 0; i < qdd_target_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qdd_target)); + memcpy( &(this->qdd_target[i]), &(this->st_qdd_target), sizeof(float)); + } + uint8_t i_target_lengthT = *(inbuffer + offset++); + if(i_target_lengthT > i_target_length) + this->i_target = (float*)realloc(this->i_target, i_target_lengthT * sizeof(float)); + offset += 3; + i_target_length = i_target_lengthT; + for( uint8_t i = 0; i < i_target_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_i_target)); + memcpy( &(this->i_target[i]), &(this->st_i_target), sizeof(float)); + } + uint8_t m_target_lengthT = *(inbuffer + offset++); + if(m_target_lengthT > m_target_length) + this->m_target = (float*)realloc(this->m_target, m_target_lengthT * sizeof(float)); + offset += 3; + m_target_length = m_target_lengthT; + for( uint8_t i = 0; i < m_target_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_m_target)); + memcpy( &(this->m_target[i]), &(this->st_m_target), sizeof(float)); + } + uint8_t q_actual_lengthT = *(inbuffer + offset++); + if(q_actual_lengthT > q_actual_length) + this->q_actual = (float*)realloc(this->q_actual, q_actual_lengthT * sizeof(float)); + offset += 3; + q_actual_length = q_actual_lengthT; + for( uint8_t i = 0; i < q_actual_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_q_actual)); + memcpy( &(this->q_actual[i]), &(this->st_q_actual), sizeof(float)); + } + uint8_t qd_actual_lengthT = *(inbuffer + offset++); + if(qd_actual_lengthT > qd_actual_length) + this->qd_actual = (float*)realloc(this->qd_actual, qd_actual_lengthT * sizeof(float)); + offset += 3; + qd_actual_length = qd_actual_lengthT; + for( uint8_t i = 0; i < qd_actual_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qd_actual)); + memcpy( &(this->qd_actual[i]), &(this->st_qd_actual), sizeof(float)); + } + uint8_t i_actual_lengthT = *(inbuffer + offset++); + if(i_actual_lengthT > i_actual_length) + this->i_actual = (float*)realloc(this->i_actual, i_actual_lengthT * sizeof(float)); + offset += 3; + i_actual_length = i_actual_lengthT; + for( uint8_t i = 0; i < i_actual_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_i_actual)); + memcpy( &(this->i_actual[i]), &(this->st_i_actual), sizeof(float)); + } + uint8_t tool_acc_values_lengthT = *(inbuffer + offset++); + if(tool_acc_values_lengthT > tool_acc_values_length) + this->tool_acc_values = (float*)realloc(this->tool_acc_values, tool_acc_values_lengthT * sizeof(float)); + offset += 3; + tool_acc_values_length = tool_acc_values_lengthT; + for( uint8_t i = 0; i < tool_acc_values_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tool_acc_values)); + memcpy( &(this->tool_acc_values[i]), &(this->st_tool_acc_values), sizeof(float)); + } + uint8_t tcp_force_lengthT = *(inbuffer + offset++); + if(tcp_force_lengthT > tcp_force_length) + this->tcp_force = (float*)realloc(this->tcp_force, tcp_force_lengthT * sizeof(float)); + offset += 3; + tcp_force_length = tcp_force_lengthT; + for( uint8_t i = 0; i < tcp_force_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tcp_force)); + memcpy( &(this->tcp_force[i]), &(this->st_tcp_force), sizeof(float)); + } + uint8_t tool_vector_lengthT = *(inbuffer + offset++); + if(tool_vector_lengthT > tool_vector_length) + this->tool_vector = (float*)realloc(this->tool_vector, tool_vector_lengthT * sizeof(float)); + offset += 3; + tool_vector_length = tool_vector_lengthT; + for( uint8_t i = 0; i < tool_vector_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tool_vector)); + memcpy( &(this->tool_vector[i]), &(this->st_tool_vector), sizeof(float)); + } + uint8_t tcp_speed_lengthT = *(inbuffer + offset++); + if(tcp_speed_lengthT > tcp_speed_length) + this->tcp_speed = (float*)realloc(this->tcp_speed, tcp_speed_lengthT * sizeof(float)); + offset += 3; + tcp_speed_length = tcp_speed_lengthT; + for( uint8_t i = 0; i < tcp_speed_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tcp_speed)); + memcpy( &(this->tcp_speed[i]), &(this->st_tcp_speed), sizeof(float)); + } + offset += deserializeAvrFloat64(inbuffer + offset, &(this->digital_input_bits)); + uint8_t motor_temperatures_lengthT = *(inbuffer + offset++); + if(motor_temperatures_lengthT > motor_temperatures_length) + this->motor_temperatures = (float*)realloc(this->motor_temperatures, motor_temperatures_lengthT * sizeof(float)); + offset += 3; + motor_temperatures_length = motor_temperatures_lengthT; + for( uint8_t i = 0; i < motor_temperatures_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_motor_temperatures)); + memcpy( &(this->motor_temperatures[i]), &(this->st_motor_temperatures), sizeof(float)); + } + offset += deserializeAvrFloat64(inbuffer + offset, &(this->controller_timer)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->test_value)); + offset += deserializeAvrFloat64(inbuffer + offset, &(this->robot_mode)); + uint8_t joint_modes_lengthT = *(inbuffer + offset++); + if(joint_modes_lengthT > joint_modes_length) + this->joint_modes = (float*)realloc(this->joint_modes, joint_modes_lengthT * sizeof(float)); + offset += 3; + joint_modes_length = joint_modes_lengthT; + for( uint8_t i = 0; i < joint_modes_length; i++){ + offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_joint_modes)); + memcpy( &(this->joint_modes[i]), &(this->st_joint_modes), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "ur_msgs/RobotStateRTMsg"; }; + const char * getMD5(){ return "ce6feddd3ccb4ca7dbcd0ff105b603c7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/SetIO.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,145 @@ +#ifndef _ROS_SERVICE_SetIO_h +#define _ROS_SERVICE_SetIO_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + +static const char SETIO[] = "ur_msgs/SetIO"; + + class SetIORequest : public ros::Msg + { + public: + int8_t fun; + int8_t pin; + float state; + + SetIORequest(): + fun(0), + pin(0), + state(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_fun; + u_fun.real = this->fun; + *(outbuffer + offset + 0) = (u_fun.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->fun); + union { + int8_t real; + uint8_t base; + } u_pin; + u_pin.real = this->pin; + *(outbuffer + offset + 0) = (u_pin.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->pin); + union { + float real; + uint32_t base; + } u_state; + u_state.real = this->state; + *(outbuffer + offset + 0) = (u_state.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_state.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_state.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_state.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->state); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_fun; + u_fun.base = 0; + u_fun.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->fun = u_fun.real; + offset += sizeof(this->fun); + union { + int8_t real; + uint8_t base; + } u_pin; + u_pin.base = 0; + u_pin.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->pin = u_pin.real; + offset += sizeof(this->pin); + union { + float real; + uint32_t base; + } u_state; + u_state.base = 0; + u_state.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_state.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->state = u_state.real; + offset += sizeof(this->state); + return offset; + } + + const char * getType(){ return SETIO; }; + const char * getMD5(){ return "cbb7d56b1142033251cb8df226edd774"; }; + + }; + + class SetIOResponse : public ros::Msg + { + public: + bool success; + + SetIOResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return SETIO; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class SetIO { + public: + typedef SetIORequest Request; + typedef SetIOResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ur_msgs/SetPayload.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,111 @@ +#ifndef _ROS_SERVICE_SetPayload_h +#define _ROS_SERVICE_SetPayload_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace ur_msgs +{ + +static const char SETPAYLOAD[] = "ur_msgs/SetPayload"; + + class SetPayloadRequest : public ros::Msg + { + public: + float payload; + + SetPayloadRequest(): + payload(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_payload; + u_payload.real = this->payload; + *(outbuffer + offset + 0) = (u_payload.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_payload.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_payload.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_payload.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->payload); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_payload; + u_payload.base = 0; + u_payload.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_payload.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_payload.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_payload.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->payload = u_payload.real; + offset += sizeof(this->payload); + return offset; + } + + const char * getType(){ return SETPAYLOAD; }; + const char * getMD5(){ return "d12269f931817591aa52047629ca66ca"; }; + + }; + + class SetPayloadResponse : public ros::Msg + { + public: + bool success; + + SetPayloadResponse(): + success(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + return offset; + } + + const char * getType(){ return SETPAYLOAD; }; + const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; + + }; + + class SetPayload { + public: + typedef SetPayloadRequest Request; + typedef SetPayloadResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/ImageMarker.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,241 @@ +#ifndef _ROS_visualization_msgs_ImageMarker_h +#define _ROS_visualization_msgs_ImageMarker_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" +#include "std_msgs/ColorRGBA.h" +#include "ros/duration.h" + +namespace visualization_msgs +{ + + class ImageMarker : public ros::Msg + { + public: + std_msgs::Header header; + const char* ns; + int32_t id; + int32_t type; + int32_t action; + geometry_msgs::Point position; + float scale; + std_msgs::ColorRGBA outline_color; + uint8_t filled; + std_msgs::ColorRGBA fill_color; + ros::Duration lifetime; + uint8_t points_length; + geometry_msgs::Point st_points; + geometry_msgs::Point * points; + uint8_t outline_colors_length; + std_msgs::ColorRGBA st_outline_colors; + std_msgs::ColorRGBA * outline_colors; + enum { CIRCLE = 0 }; + enum { LINE_STRIP = 1 }; + enum { LINE_LIST = 2 }; + enum { POLYGON = 3 }; + enum { POINTS = 4 }; + enum { ADD = 0 }; + enum { REMOVE = 1 }; + + ImageMarker(): + header(), + ns(""), + id(0), + type(0), + action(0), + position(), + scale(0), + outline_color(), + filled(0), + fill_color(), + lifetime(), + points_length(0), points(NULL), + outline_colors_length(0), outline_colors(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_ns = strlen(this->ns); + memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->ns, length_ns); + offset += length_ns; + union { + int32_t real; + uint32_t base; + } u_id; + u_id.real = this->id; + *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_type; + u_type.real = this->type; + *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->type); + union { + int32_t real; + uint32_t base; + } u_action; + u_action.real = this->action; + *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->action); + offset += this->position.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_scale; + u_scale.real = this->scale; + *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scale); + offset += this->outline_color.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->filled >> (8 * 0)) & 0xFF; + offset += sizeof(this->filled); + offset += this->fill_color.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->lifetime.sec); + *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->lifetime.nsec); + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = outline_colors_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < outline_colors_length; i++){ + offset += this->outline_colors[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_ns; + memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_ns; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_ns-1]=0; + this->ns = (char *)(inbuffer + offset-1); + offset += length_ns; + union { + int32_t real; + uint32_t base; + } u_id; + u_id.base = 0; + u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->id = u_id.real; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_type; + u_type.base = 0; + u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->type = u_type.real; + offset += sizeof(this->type); + union { + int32_t real; + uint32_t base; + } u_action; + u_action.base = 0; + u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->action = u_action.real; + offset += sizeof(this->action); + offset += this->position.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_scale; + u_scale.base = 0; + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scale = u_scale.real; + offset += sizeof(this->scale); + offset += this->outline_color.deserialize(inbuffer + offset); + this->filled = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->filled); + offset += this->fill_color.deserialize(inbuffer + offset); + this->lifetime.sec = ((uint32_t) (*(inbuffer + offset))); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->lifetime.sec); + this->lifetime.nsec = ((uint32_t) (*(inbuffer + offset))); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->lifetime.nsec); + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point)); + } + uint8_t outline_colors_lengthT = *(inbuffer + offset++); + if(outline_colors_lengthT > outline_colors_length) + this->outline_colors = (std_msgs::ColorRGBA*)realloc(this->outline_colors, outline_colors_lengthT * sizeof(std_msgs::ColorRGBA)); + offset += 3; + outline_colors_length = outline_colors_lengthT; + for( uint8_t i = 0; i < outline_colors_length; i++){ + offset += this->st_outline_colors.deserialize(inbuffer + offset); + memcpy( &(this->outline_colors[i]), &(this->st_outline_colors), sizeof(std_msgs::ColorRGBA)); + } + return offset; + } + + const char * getType(){ return "visualization_msgs/ImageMarker"; }; + const char * getMD5(){ return "1de93c67ec8858b831025a08fbf1b35c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarker.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,145 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarker_h +#define _ROS_visualization_msgs_InteractiveMarker_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "visualization_msgs/MenuEntry.h" +#include "visualization_msgs/InteractiveMarkerControl.h" + +namespace visualization_msgs +{ + + class InteractiveMarker : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose pose; + const char* name; + const char* description; + float scale; + uint8_t menu_entries_length; + visualization_msgs::MenuEntry st_menu_entries; + visualization_msgs::MenuEntry * menu_entries; + uint8_t controls_length; + visualization_msgs::InteractiveMarkerControl st_controls; + visualization_msgs::InteractiveMarkerControl * controls; + + InteractiveMarker(): + header(), + pose(), + name(""), + description(""), + scale(0), + menu_entries_length(0), menu_entries(NULL), + controls_length(0), controls(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_description = strlen(this->description); + memcpy(outbuffer + offset, &length_description, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->description, length_description); + offset += length_description; + union { + float real; + uint32_t base; + } u_scale; + u_scale.real = this->scale; + *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scale); + *(outbuffer + offset++) = menu_entries_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < menu_entries_length; i++){ + offset += this->menu_entries[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = controls_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < controls_length; i++){ + offset += this->controls[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_description; + memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_description; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_description-1]=0; + this->description = (char *)(inbuffer + offset-1); + offset += length_description; + union { + float real; + uint32_t base; + } u_scale; + u_scale.base = 0; + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scale = u_scale.real; + offset += sizeof(this->scale); + uint8_t menu_entries_lengthT = *(inbuffer + offset++); + if(menu_entries_lengthT > menu_entries_length) + this->menu_entries = (visualization_msgs::MenuEntry*)realloc(this->menu_entries, menu_entries_lengthT * sizeof(visualization_msgs::MenuEntry)); + offset += 3; + menu_entries_length = menu_entries_lengthT; + for( uint8_t i = 0; i < menu_entries_length; i++){ + offset += this->st_menu_entries.deserialize(inbuffer + offset); + memcpy( &(this->menu_entries[i]), &(this->st_menu_entries), sizeof(visualization_msgs::MenuEntry)); + } + uint8_t controls_lengthT = *(inbuffer + offset++); + if(controls_lengthT > controls_length) + this->controls = (visualization_msgs::InteractiveMarkerControl*)realloc(this->controls, controls_lengthT * sizeof(visualization_msgs::InteractiveMarkerControl)); + offset += 3; + controls_length = controls_lengthT; + for( uint8_t i = 0; i < controls_length; i++){ + offset += this->st_controls.deserialize(inbuffer + offset); + memcpy( &(this->controls[i]), &(this->st_controls), sizeof(visualization_msgs::InteractiveMarkerControl)); + } + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarker"; }; + const char * getMD5(){ return "311bd5f6cd6a20820ac0ba84315f4e22"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarkerControl.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,155 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarkerControl_h +#define _ROS_visualization_msgs_InteractiveMarkerControl_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Quaternion.h" +#include "visualization_msgs/Marker.h" + +namespace visualization_msgs +{ + + class InteractiveMarkerControl : public ros::Msg + { + public: + const char* name; + geometry_msgs::Quaternion orientation; + uint8_t orientation_mode; + uint8_t interaction_mode; + bool always_visible; + uint8_t markers_length; + visualization_msgs::Marker st_markers; + visualization_msgs::Marker * markers; + bool independent_marker_orientation; + const char* description; + enum { INHERIT = 0 }; + enum { FIXED = 1 }; + enum { VIEW_FACING = 2 }; + enum { NONE = 0 }; + enum { MENU = 1 }; + enum { BUTTON = 2 }; + enum { MOVE_AXIS = 3 }; + enum { MOVE_PLANE = 4 }; + enum { ROTATE_AXIS = 5 }; + enum { MOVE_ROTATE = 6 }; + enum { MOVE_3D = 7 }; + enum { ROTATE_3D = 8 }; + enum { MOVE_ROTATE_3D = 9 }; + + InteractiveMarkerControl(): + name(""), + orientation(), + orientation_mode(0), + interaction_mode(0), + always_visible(0), + markers_length(0), markers(NULL), + independent_marker_orientation(0), + description("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + offset += this->orientation.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF; + offset += sizeof(this->orientation_mode); + *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF; + offset += sizeof(this->interaction_mode); + union { + bool real; + uint8_t base; + } u_always_visible; + u_always_visible.real = this->always_visible; + *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->always_visible); + *(outbuffer + offset++) = markers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->markers[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_independent_marker_orientation; + u_independent_marker_orientation.real = this->independent_marker_orientation; + *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->independent_marker_orientation); + uint32_t length_description = strlen(this->description); + memcpy(outbuffer + offset, &length_description, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->description, length_description); + offset += length_description; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + offset += this->orientation.deserialize(inbuffer + offset); + this->orientation_mode = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->orientation_mode); + this->interaction_mode = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->interaction_mode); + union { + bool real; + uint8_t base; + } u_always_visible; + u_always_visible.base = 0; + u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->always_visible = u_always_visible.real; + offset += sizeof(this->always_visible); + uint8_t markers_lengthT = *(inbuffer + offset++); + if(markers_lengthT > markers_length) + this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker)); + offset += 3; + markers_length = markers_lengthT; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->st_markers.deserialize(inbuffer + offset); + memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker)); + } + union { + bool real; + uint8_t base; + } u_independent_marker_orientation; + u_independent_marker_orientation.base = 0; + u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->independent_marker_orientation = u_independent_marker_orientation.real; + offset += sizeof(this->independent_marker_orientation); + uint32_t length_description; + memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_description; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_description-1]=0; + this->description = (char *)(inbuffer + offset-1); + offset += length_description; + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; }; + const char * getMD5(){ return "e3a939c98cdd4f709d8e1dec2a9c3f37"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarkerFeedback.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,142 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarkerFeedback_h +#define _ROS_visualization_msgs_InteractiveMarkerFeedback_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Point.h" + +namespace visualization_msgs +{ + + class InteractiveMarkerFeedback : public ros::Msg + { + public: + std_msgs::Header header; + const char* client_id; + const char* marker_name; + const char* control_name; + uint8_t event_type; + geometry_msgs::Pose pose; + uint32_t menu_entry_id; + geometry_msgs::Point mouse_point; + bool mouse_point_valid; + enum { KEEP_ALIVE = 0 }; + enum { POSE_UPDATE = 1 }; + enum { MENU_SELECT = 2 }; + enum { BUTTON_CLICK = 3 }; + enum { MOUSE_DOWN = 4 }; + enum { MOUSE_UP = 5 }; + + InteractiveMarkerFeedback(): + header(), + client_id(""), + marker_name(""), + control_name(""), + event_type(0), + pose(), + menu_entry_id(0), + mouse_point(), + mouse_point_valid(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_client_id = strlen(this->client_id); + memcpy(outbuffer + offset, &length_client_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->client_id, length_client_id); + offset += length_client_id; + uint32_t length_marker_name = strlen(this->marker_name); + memcpy(outbuffer + offset, &length_marker_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->marker_name, length_marker_name); + offset += length_marker_name; + uint32_t length_control_name = strlen(this->control_name); + memcpy(outbuffer + offset, &length_control_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->control_name, length_control_name); + offset += length_control_name; + *(outbuffer + offset + 0) = (this->event_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->event_type); + offset += this->pose.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->menu_entry_id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->menu_entry_id >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->menu_entry_id >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->menu_entry_id >> (8 * 3)) & 0xFF; + offset += sizeof(this->menu_entry_id); + offset += this->mouse_point.serialize(outbuffer + offset); + union { + bool real; + uint8_t base; + } u_mouse_point_valid; + u_mouse_point_valid.real = this->mouse_point_valid; + *(outbuffer + offset + 0) = (u_mouse_point_valid.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->mouse_point_valid); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_client_id; + memcpy(&length_client_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_client_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_client_id-1]=0; + this->client_id = (char *)(inbuffer + offset-1); + offset += length_client_id; + uint32_t length_marker_name; + memcpy(&length_marker_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_marker_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_marker_name-1]=0; + this->marker_name = (char *)(inbuffer + offset-1); + offset += length_marker_name; + uint32_t length_control_name; + memcpy(&length_control_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_control_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_control_name-1]=0; + this->control_name = (char *)(inbuffer + offset-1); + offset += length_control_name; + this->event_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->event_type); + offset += this->pose.deserialize(inbuffer + offset); + this->menu_entry_id = ((uint32_t) (*(inbuffer + offset))); + this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->menu_entry_id); + offset += this->mouse_point.deserialize(inbuffer + offset); + union { + bool real; + uint8_t base; + } u_mouse_point_valid; + u_mouse_point_valid.base = 0; + u_mouse_point_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->mouse_point_valid = u_mouse_point_valid.real; + offset += sizeof(this->mouse_point_valid); + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarkerFeedback"; }; + const char * getMD5(){ return "ab0f1eee058667e28c19ff3ffc3f4b78"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarkerInit.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,98 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarkerInit_h +#define _ROS_visualization_msgs_InteractiveMarkerInit_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "visualization_msgs/InteractiveMarker.h" + +namespace visualization_msgs +{ + + class InteractiveMarkerInit : public ros::Msg + { + public: + const char* server_id; + uint64_t seq_num; + uint8_t markers_length; + visualization_msgs::InteractiveMarker st_markers; + visualization_msgs::InteractiveMarker * markers; + + InteractiveMarkerInit(): + server_id(""), + seq_num(0), + markers_length(0), markers(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_server_id = strlen(this->server_id); + memcpy(outbuffer + offset, &length_server_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->server_id, length_server_id); + offset += length_server_id; + union { + uint64_t real; + uint32_t base; + } u_seq_num; + u_seq_num.real = this->seq_num; + *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq_num); + *(outbuffer + offset++) = markers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->markers[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_server_id; + memcpy(&length_server_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_server_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_server_id-1]=0; + this->server_id = (char *)(inbuffer + offset-1); + offset += length_server_id; + union { + uint64_t real; + uint32_t base; + } u_seq_num; + u_seq_num.base = 0; + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->seq_num = u_seq_num.real; + offset += sizeof(this->seq_num); + uint8_t markers_lengthT = *(inbuffer + offset++); + if(markers_lengthT > markers_length) + this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker)); + offset += 3; + markers_length = markers_lengthT; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->st_markers.deserialize(inbuffer + offset); + memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker)); + } + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarkerInit"; }; + const char * getMD5(){ return "aa2f1dcea79533d1710675195653028d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarkerPose.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarkerPose_h +#define _ROS_visualization_msgs_InteractiveMarkerPose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" + +namespace visualization_msgs +{ + + class InteractiveMarkerPose : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose pose; + const char* name; + + InteractiveMarkerPose(): + header(), + pose(), + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + uint32_t length_name = strlen(this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarkerPose"; }; + const char * getMD5(){ return "a6e6833209a196a38d798dadb02c81f8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/InteractiveMarkerUpdate.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,159 @@ +#ifndef _ROS_visualization_msgs_InteractiveMarkerUpdate_h +#define _ROS_visualization_msgs_InteractiveMarkerUpdate_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "visualization_msgs/InteractiveMarker.h" +#include "visualization_msgs/InteractiveMarkerPose.h" + +namespace visualization_msgs +{ + + class InteractiveMarkerUpdate : public ros::Msg + { + public: + const char* server_id; + uint64_t seq_num; + uint8_t type; + uint8_t markers_length; + visualization_msgs::InteractiveMarker st_markers; + visualization_msgs::InteractiveMarker * markers; + uint8_t poses_length; + visualization_msgs::InteractiveMarkerPose st_poses; + visualization_msgs::InteractiveMarkerPose * poses; + uint8_t erases_length; + char* st_erases; + char* * erases; + enum { KEEP_ALIVE = 0 }; + enum { UPDATE = 1 }; + + InteractiveMarkerUpdate(): + server_id(""), + seq_num(0), + type(0), + markers_length(0), markers(NULL), + poses_length(0), poses(NULL), + erases_length(0), erases(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_server_id = strlen(this->server_id); + memcpy(outbuffer + offset, &length_server_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->server_id, length_server_id); + offset += length_server_id; + union { + uint64_t real; + uint32_t base; + } u_seq_num; + u_seq_num.real = this->seq_num; + *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq_num); + *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; + offset += sizeof(this->type); + *(outbuffer + offset++) = markers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->markers[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->poses[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = erases_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < erases_length; i++){ + uint32_t length_erasesi = strlen(this->erases[i]); + memcpy(outbuffer + offset, &length_erasesi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->erases[i], length_erasesi); + offset += length_erasesi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_server_id; + memcpy(&length_server_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_server_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_server_id-1]=0; + this->server_id = (char *)(inbuffer + offset-1); + offset += length_server_id; + union { + uint64_t real; + uint32_t base; + } u_seq_num; + u_seq_num.base = 0; + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->seq_num = u_seq_num.real; + offset += sizeof(this->seq_num); + this->type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->type); + uint8_t markers_lengthT = *(inbuffer + offset++); + if(markers_lengthT > markers_length) + this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker)); + offset += 3; + markers_length = markers_lengthT; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->st_markers.deserialize(inbuffer + offset); + memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker)); + } + uint8_t poses_lengthT = *(inbuffer + offset++); + if(poses_lengthT > poses_length) + this->poses = (visualization_msgs::InteractiveMarkerPose*)realloc(this->poses, poses_lengthT * sizeof(visualization_msgs::InteractiveMarkerPose)); + offset += 3; + poses_length = poses_lengthT; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->st_poses.deserialize(inbuffer + offset); + memcpy( &(this->poses[i]), &(this->st_poses), sizeof(visualization_msgs::InteractiveMarkerPose)); + } + uint8_t erases_lengthT = *(inbuffer + offset++); + if(erases_lengthT > erases_length) + this->erases = (char**)realloc(this->erases, erases_lengthT * sizeof(char*)); + offset += 3; + erases_length = erases_lengthT; + for( uint8_t i = 0; i < erases_length; i++){ + uint32_t length_st_erases; + memcpy(&length_st_erases, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_erases; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_erases-1]=0; + this->st_erases = (char *)(inbuffer + offset-1); + offset += length_st_erases; + memcpy( &(this->erases[i]), &(this->st_erases), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "visualization_msgs/InteractiveMarkerUpdate"; }; + const char * getMD5(){ return "83e22f99d3b31fde725e0a338200e036"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/Marker.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,288 @@ +#ifndef _ROS_visualization_msgs_Marker_h +#define _ROS_visualization_msgs_Marker_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/Vector3.h" +#include "std_msgs/ColorRGBA.h" +#include "ros/duration.h" +#include "geometry_msgs/Point.h" + +namespace visualization_msgs +{ + + class Marker : public ros::Msg + { + public: + std_msgs::Header header; + const char* ns; + int32_t id; + int32_t type; + int32_t action; + geometry_msgs::Pose pose; + geometry_msgs::Vector3 scale; + std_msgs::ColorRGBA color; + ros::Duration lifetime; + bool frame_locked; + uint8_t points_length; + geometry_msgs::Point st_points; + geometry_msgs::Point * points; + uint8_t colors_length; + std_msgs::ColorRGBA st_colors; + std_msgs::ColorRGBA * colors; + const char* text; + const char* mesh_resource; + bool mesh_use_embedded_materials; + enum { ARROW = 0 }; + enum { CUBE = 1 }; + enum { SPHERE = 2 }; + enum { CYLINDER = 3 }; + enum { LINE_STRIP = 4 }; + enum { LINE_LIST = 5 }; + enum { CUBE_LIST = 6 }; + enum { SPHERE_LIST = 7 }; + enum { POINTS = 8 }; + enum { TEXT_VIEW_FACING = 9 }; + enum { MESH_RESOURCE = 10 }; + enum { TRIANGLE_LIST = 11 }; + enum { ADD = 0 }; + enum { MODIFY = 0 }; + enum { DELETE = 2 }; + + Marker(): + header(), + ns(""), + id(0), + type(0), + action(0), + pose(), + scale(), + color(), + lifetime(), + frame_locked(0), + points_length(0), points(NULL), + colors_length(0), colors(NULL), + text(""), + mesh_resource(""), + mesh_use_embedded_materials(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_ns = strlen(this->ns); + memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->ns, length_ns); + offset += length_ns; + union { + int32_t real; + uint32_t base; + } u_id; + u_id.real = this->id; + *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_type; + u_type.real = this->type; + *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->type); + union { + int32_t real; + uint32_t base; + } u_action; + u_action.real = this->action; + *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->action); + offset += this->pose.serialize(outbuffer + offset); + offset += this->scale.serialize(outbuffer + offset); + offset += this->color.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->lifetime.sec); + *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->lifetime.nsec); + union { + bool real; + uint8_t base; + } u_frame_locked; + u_frame_locked.real = this->frame_locked; + *(outbuffer + offset + 0) = (u_frame_locked.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->frame_locked); + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = colors_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < colors_length; i++){ + offset += this->colors[i].serialize(outbuffer + offset); + } + uint32_t length_text = strlen(this->text); + memcpy(outbuffer + offset, &length_text, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->text, length_text); + offset += length_text; + uint32_t length_mesh_resource = strlen(this->mesh_resource); + memcpy(outbuffer + offset, &length_mesh_resource, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->mesh_resource, length_mesh_resource); + offset += length_mesh_resource; + union { + bool real; + uint8_t base; + } u_mesh_use_embedded_materials; + u_mesh_use_embedded_materials.real = this->mesh_use_embedded_materials; + *(outbuffer + offset + 0) = (u_mesh_use_embedded_materials.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->mesh_use_embedded_materials); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_ns; + memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_ns; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_ns-1]=0; + this->ns = (char *)(inbuffer + offset-1); + offset += length_ns; + union { + int32_t real; + uint32_t base; + } u_id; + u_id.base = 0; + u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->id = u_id.real; + offset += sizeof(this->id); + union { + int32_t real; + uint32_t base; + } u_type; + u_type.base = 0; + u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->type = u_type.real; + offset += sizeof(this->type); + union { + int32_t real; + uint32_t base; + } u_action; + u_action.base = 0; + u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->action = u_action.real; + offset += sizeof(this->action); + offset += this->pose.deserialize(inbuffer + offset); + offset += this->scale.deserialize(inbuffer + offset); + offset += this->color.deserialize(inbuffer + offset); + this->lifetime.sec = ((uint32_t) (*(inbuffer + offset))); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->lifetime.sec); + this->lifetime.nsec = ((uint32_t) (*(inbuffer + offset))); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->lifetime.nsec); + union { + bool real; + uint8_t base; + } u_frame_locked; + u_frame_locked.base = 0; + u_frame_locked.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->frame_locked = u_frame_locked.real; + offset += sizeof(this->frame_locked); + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point)); + } + uint8_t colors_lengthT = *(inbuffer + offset++); + if(colors_lengthT > colors_length) + this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA)); + offset += 3; + colors_length = colors_lengthT; + for( uint8_t i = 0; i < colors_length; i++){ + offset += this->st_colors.deserialize(inbuffer + offset); + memcpy( &(this->colors[i]), &(this->st_colors), sizeof(std_msgs::ColorRGBA)); + } + uint32_t length_text; + memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_text; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_text-1]=0; + this->text = (char *)(inbuffer + offset-1); + offset += length_text; + uint32_t length_mesh_resource; + memcpy(&length_mesh_resource, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_mesh_resource; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_mesh_resource-1]=0; + this->mesh_resource = (char *)(inbuffer + offset-1); + offset += length_mesh_resource; + union { + bool real; + uint8_t base; + } u_mesh_use_embedded_materials; + u_mesh_use_embedded_materials.base = 0; + u_mesh_use_embedded_materials.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->mesh_use_embedded_materials = u_mesh_use_embedded_materials.real; + offset += sizeof(this->mesh_use_embedded_materials); + return offset; + } + + const char * getType(){ return "visualization_msgs/Marker"; }; + const char * getMD5(){ return "18326976df9d29249efc939e00342cde"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/MarkerArray.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_visualization_msgs_MarkerArray_h +#define _ROS_visualization_msgs_MarkerArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "visualization_msgs/Marker.h" + +namespace visualization_msgs +{ + + class MarkerArray : public ros::Msg + { + public: + uint8_t markers_length; + visualization_msgs::Marker st_markers; + visualization_msgs::Marker * markers; + + MarkerArray(): + markers_length(0), markers(NULL) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = markers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->markers[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t markers_lengthT = *(inbuffer + offset++); + if(markers_lengthT > markers_length) + this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker)); + offset += 3; + markers_length = markers_lengthT; + for( uint8_t i = 0; i < markers_length; i++){ + offset += this->st_markers.deserialize(inbuffer + offset); + memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker)); + } + return offset; + } + + const char * getType(){ return "visualization_msgs/MarkerArray"; }; + const char * getMD5(){ return "90da67007c26525f655c1c269094e39f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/visualization_msgs/MenuEntry.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,103 @@ +#ifndef _ROS_visualization_msgs_MenuEntry_h +#define _ROS_visualization_msgs_MenuEntry_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace visualization_msgs +{ + + class MenuEntry : public ros::Msg + { + public: + uint32_t id; + uint32_t parent_id; + const char* title; + const char* command; + uint8_t command_type; + enum { FEEDBACK = 0 }; + enum { ROSRUN = 1 }; + enum { ROSLAUNCH = 2 }; + + MenuEntry(): + id(0), + parent_id(0), + title(""), + command(""), + command_type(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->id >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->id >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->id >> (8 * 3)) & 0xFF; + offset += sizeof(this->id); + *(outbuffer + offset + 0) = (this->parent_id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->parent_id >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->parent_id >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->parent_id >> (8 * 3)) & 0xFF; + offset += sizeof(this->parent_id); + uint32_t length_title = strlen(this->title); + memcpy(outbuffer + offset, &length_title, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->title, length_title); + offset += length_title; + uint32_t length_command = strlen(this->command); + memcpy(outbuffer + offset, &length_command, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->command, length_command); + offset += length_command; + *(outbuffer + offset + 0) = (this->command_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->command_type); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->id = ((uint32_t) (*(inbuffer + offset))); + this->id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->id); + this->parent_id = ((uint32_t) (*(inbuffer + offset))); + this->parent_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->parent_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->parent_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->parent_id); + uint32_t length_title; + memcpy(&length_title, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_title; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_title-1]=0; + this->title = (char *)(inbuffer + offset-1); + offset += length_title; + uint32_t length_command; + memcpy(&length_command, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_command; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_command-1]=0; + this->command = (char *)(inbuffer + offset-1); + offset += length_command; + this->command_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->command_type); + return offset; + } + + const char * getType(){ return "visualization_msgs/MenuEntry"; }; + const char * getMD5(){ return "b90ec63024573de83b57aa93eb39be2d"; }; + + }; + +} +#endif