diff --git a/smart_device_protocol/.gitignore b/smart_device_protocol/.gitignore new file mode 100644 index 000000000..f4a99a34b --- /dev/null +++ b/smart_device_protocol/.gitignore @@ -0,0 +1,54 @@ +devel/ +logs/ +build/ +bin/ +lib/ +msg_gen/ +srv_gen/ +msg/*Action.msg +msg/*ActionFeedback.msg +msg/*ActionGoal.msg +msg/*ActionResult.msg +msg/*Feedback.msg +msg/*Goal.msg +msg/*Result.msg +msg/_*.py +build_isolated/ +devel_isolated/ + +# Generated by dynamic reconfigure +*.cfgc +/cfg/cpp/ +/cfg/*.py + +# Ignore generated docs +*.dox +*.wikidoc + +# eclipse stuff +.project +.cproject + +# qcreator stuff +CMakeLists.txt.user + +srv/_*.py +*.pcd +*.pyc +qtcreator-* +*.user + +/planning/cfg +/planning/docs +/planning/src + +*~ + +# Emacs +.#* + +# Catkin custom files +CATKIN_IGNORE + +# +*.vscode diff --git a/smart_device_protocol/CMakeLists.txt b/smart_device_protocol/CMakeLists.txt new file mode 100644 index 000000000..52a87ed35 --- /dev/null +++ b/smart_device_protocol/CMakeLists.txt @@ -0,0 +1,47 @@ +cmake_minimum_required(VERSION 2.8.3) +project(smart_device_protocol) + +find_package(catkin REQUIRED COMPONENTS message_generation catkin_virtualenv std_msgs) + +catkin_generate_virtualenv( + PYTHON_INTERPRETER python3 + CHECK_VENV FALSE + USE_SYSTEM_PACKAGES FALSE + ISOLATE_REQUIREMENTS TRUE +) + +catkin_python_setup() + +add_message_files( + FILES + Packet.msg + UWBDistance.msg +) + +generate_messages( + DEPENDENCIES + std_msgs +) + +catkin_package( + CATKIN_DEPENDS message_runtime +) + +file(GLOB ${PROJECT_NAME}_node_scripts ${PROJECT_SOURCE_DIR}/node_scripts/*) + +catkin_install_python( + PROGRAMS ${${PROJECT_NAME}_node_scripts} + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + + file(GLOB ${PROJECT_NAME}_test_node_scripts ${PROJECT_SOURCE_DIR}/tests/*.py) + catkin_install_python( + PROGRAMS ${${PROJECT_NAME}_test_node_scripts} + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + add_rostest(tests/sdp_v2_interface_rostest.test) +endif() diff --git a/smart_device_protocol/LICENSE b/smart_device_protocol/LICENSE new file mode 100644 index 000000000..29d7e1c6a --- /dev/null +++ b/smart_device_protocol/LICENSE @@ -0,0 +1,28 @@ +BSD 3-Clause License + +Copyright (c) 2023, Koki Shinjo + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +2. 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. + +3. Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products 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 HOLDER 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. diff --git a/smart_device_protocol/README.md b/smart_device_protocol/README.md new file mode 100644 index 000000000..c80bf3a84 --- /dev/null +++ b/smart_device_protocol/README.md @@ -0,0 +1,196 @@ +
+ +
+ +bytes: + data = struct.pack("0 and len(serialization_format) > 0: + interface_descriptions.append( + (packet_description, serialization_format) + ) + return MetaFrame( + device_name=device_name, interface_descriptions=interface_descriptions + ) + + +class DataFrame(BaseFrame): + def __init__( + self, + packet_description: str, + content: List[Union[bool, int, float, str]], + serialization_format=None, + ): + self._packet_description = packet_description + if serialization_format is not None: + self._serialization_format = serialization_format + else: + serialization_format = "" + for entry in content: + if type(entry) is bool: + serialization_format += "?" + elif type(entry) is int: + serialization_format += "i" + elif type(entry) is float: + serialization_format += "f" + elif type(entry) is str: + encoded_entry = entry.encode("utf-8") + if len(encoded_entry) <= 16: + serialization_format += "s" + elif len(encoded_entry) <= 64: + serialization_format += "S" + else: + raise ValueError( + f"String entry of content is longer than 64 bytes: {len(encoded_entry)}" + ) + else: + raise ValueError( + f"There is an unknown type of content: {type(entry)}" + ) + self._serialization_format = serialization_format + self._content = content + + def __repr__(self): + output = f"packet_description: [{self._packet_description}]\n" + output += f"serialization_format: [{self._serialization_format}]\n" + output += f"content: {self._content}" + return output + + def __eq__(self, other): + if isinstance(other, MetaFrame): + return self.__dict__ == other.__dict__ + return False + + @property + def packet_description(self): + return self._packet_description + + @property + def serialization_format(self): + return self._serialization_format + + @property + def content(self): + return self._content + + @property + def interface_description(self): + return (self._packet_description, self._serialization_format) + + def to_bytes(self) -> bytes: + data: bytes = ( + struct.pack(" self._timeout: + rospy.logwarn( + "Remove timeout device: {}, {}".format( + src_address, device_interface["device_name"] + ) + ) + self._device_interfaces.pop(src_address) + + @property + def device_interfaces(self): + return self._device_interfaces + + def send( + self, target: Union[Tuple, str], frame: Union[DataFrame, MetaFrame], num_trial=1 + ): + if isinstance(target, str): + for src_address, device_interface in self._device_interfaces.items(): + if device_interface["device_name"] == target: + target_address = src_address + break + else: + raise ValueError(f"Unknown device name: {target}") + else: + target_address = target + super().send(target_address, frame, num_trial) + + +class DeviceDictSDPInterfaceWithInterfaceCallback(DeviceDictSDPInterface): + def __init__( + self, + callbacks_data: Dict[ + Tuple[str, str], Callable[[Union[List[int], Tuple[int]], List], None] + ] = {}, + callback_meta=None, + timeout: float = 10.0, + ): + self._callbacks_data = callbacks_data + self._callback_meta = callback_meta + super().__init__( + self._callback_data_for_interface, self._callback_meta, timeout + ) + + def _callback_data_for_interface(self, src_address, frame): + interface_description = frame.interface_description + if interface_description in self._callbacks_data: + self._callbacks_data[interface_description](src_address, frame) + + def register_callback(self, interface_description, callback): + self._callbacks_data[interface_description] = callback + + def unregister_callback(self, interface_description): + del self._callbacks_data[interface_description] diff --git a/smart_device_protocol/python/smart_device_protocol/utils.py b/smart_device_protocol/python/smart_device_protocol/utils.py new file mode 100644 index 000000000..c56d1ce72 --- /dev/null +++ b/smart_device_protocol/python/smart_device_protocol/utils.py @@ -0,0 +1,24 @@ +import importlib +from typing import Tuple + + +def import_ros_type(ros_type_str: str) -> type: + package_name, message_name = ros_type_str.split("/") + module = importlib.import_module(f"{package_name}.msg") + rostype = getattr(module, message_name) + return rostype + + +def address_tuple_to_str(address: Tuple) -> str: + return "{:02x}:{:02x}:{:02x}:{:02x}:{:02x}:{:02x}".format( + address[0], + address[1], + address[2], + address[3], + address[4], + address[5], + ) + + +def address_str_to_tuple(address: str) -> Tuple: + return tuple([int(x, 16) for x in address.split(":")]) diff --git a/smart_device_protocol/requirements.txt b/smart_device_protocol/requirements.txt new file mode 100644 index 000000000..e69de29bb diff --git a/smart_device_protocol/ros_lib/.gitignore b/smart_device_protocol/ros_lib/.gitignore new file mode 100644 index 000000000..57c53d50a --- /dev/null +++ b/smart_device_protocol/ros_lib/.gitignore @@ -0,0 +1 @@ +./* diff --git a/smart_device_protocol/ros_lib/ros_lib/ArduinoHardware.h b/smart_device_protocol/ros_lib/ros_lib/ArduinoHardware.h new file mode 100644 index 000000000..08fbbd5e6 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/ArduinoHardware.h @@ -0,0 +1,118 @@ +/* + * 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_ARDUINO_HARDWARE_H_ +#define ROS_ARDUINO_HARDWARE_H_ + +#if ARDUINO>=100 + #include // Arduino 1.0 +#else + #include // Arduino 0022 +#endif + +#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) || defined(__IMXRT1062__) + #if defined(USE_TEENSY_HW_SERIAL) + #define SERIAL_CLASS HardwareSerial // Teensy HW Serial + #else + #include // Teensy 3.0 and 3.1 + #define SERIAL_CLASS usb_serial_class + #endif +#elif defined(_SAM3XA_) + #include // Arduino Due + #define SERIAL_CLASS UARTClass +#elif defined(USE_USBCON) + // Arduino Leonardo USB Serial Port + #define SERIAL_CLASS Serial_ +#elif (defined(__STM32F1__) and !(defined(USE_STM32_HW_SERIAL))) or defined(SPARK) + // Stm32duino Maple mini USB Serial Port + #define SERIAL_CLASS USBSerial +#else + #include // Arduino AVR + #define SERIAL_CLASS HardwareSerial +#endif + +class ArduinoHardware { + public: + ArduinoHardware(SERIAL_CLASS* io , long baud= 57600){ + iostream = io; + baud_ = baud; + } + ArduinoHardware() + { +#if defined(USBCON) and !(defined(USE_USBCON)) + /* Leonardo support */ + iostream = &Serial1; +#elif defined(USE_TEENSY_HW_SERIAL) or defined(USE_STM32_HW_SERIAL) + iostream = &Serial1; +#else + iostream = &Serial; +#endif + baud_ = 57600; + } + ArduinoHardware(ArduinoHardware& h){ + this->iostream = h.iostream; + this->baud_ = h.baud_; + } + + void setPort(SERIAL_CLASS* io){ + this->iostream = io; + } + + void setBaud(long baud){ + this->baud_= baud; + } + + int getBaud(){return baud_;} + + void init(){ +#if defined(USE_USBCON) + // Startup delay as a fail-safe to upload a new sketch + delay(3000); +#endif + iostream->begin(baud_); + } + + int read(){return iostream->read();}; + void write(uint8_t* data, int length){ + iostream->write(data, length); + } + + unsigned long time(){return millis();} + + protected: + SERIAL_CLASS* iostream; + long baud_; +}; + +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/ArduinoTcpHardware.h b/smart_device_protocol/ros_lib/ros_lib/ArduinoTcpHardware.h new file mode 100644 index 000000000..43c508cae --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/ArduinoTcpHardware.h @@ -0,0 +1,116 @@ +/* + * 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_ARDUINO_TCP_HARDWARE_H_ +#define ROS_ARDUINO_TCP_HARDWARE_H_ + +#include +#if defined(ESP8266) + #include +#elif defined(ESP32) + #include // Using Espressif's WiFi.h +#else + #include + #include +#endif + +class ArduinoHardware { +public: + ArduinoHardware() + { + } + + void setConnection(IPAddress &server, int port = 11411) + { + server_ = server; + serverPort_ = port; + } + + IPAddress getLocalIP() + { +#if defined(ESP8266) or defined(ESP32) + return tcp_.localIP(); +#else + return Ethernet.localIP(); +#endif + } + + void init() + { + if(tcp_.connected()) + { + tcp_.stop(); + } + tcp_.connect(server_, serverPort_); + } + + int read(){ + if (tcp_.connected()) + { + return tcp_.read(); + } + else + { + tcp_.stop(); + tcp_.connect(server_, serverPort_); + } + return -1; + } + + void write(const uint8_t* data, int length) + { + tcp_.write(data, length); + } + + unsigned long time() + { + return millis(); + } + + bool connected() + { + return tcp_.connected(); + } + +protected: +#if defined(ESP8266) or defined(ESP32) + WiFiClient tcp_; +#else + EthernetClient tcp_; +#endif + IPAddress server_; + uint16_t serverPort_ = 11411; +}; + +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestAction.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestAction.h new file mode 100644 index 000000000..b3d40c9d2 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestAction.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestAction_h +#define _ROS_actionlib_TestAction_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib/TestActionGoal.h" +#include "actionlib/TestActionResult.h" +#include "actionlib/TestActionFeedback.h" + +namespace actionlib +{ + + class TestAction : public ros::Msg + { + public: + typedef actionlib::TestActionGoal _action_goal_type; + _action_goal_type action_goal; + typedef actionlib::TestActionResult _action_result_type; + _action_result_type action_result; + typedef actionlib::TestActionFeedback _action_feedback_type; + _action_feedback_type action_feedback; + + TestAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestAction"; }; + virtual const char * getMD5() override { return "991e87a72802262dfbe5d1b3cf6efc9a"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionFeedback.h new file mode 100644 index 000000000..d828823ce --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionFeedback.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestActionFeedback_h +#define _ROS_actionlib_TestActionFeedback_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestFeedback.h" + +namespace actionlib +{ + + class TestActionFeedback : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TestFeedback _feedback_type; + _feedback_type feedback; + + TestActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestActionFeedback"; }; + virtual const char * getMD5() override { return "6d3d0bf7fb3dda24779c010a9f3eb7cb"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionGoal.h new file mode 100644 index 000000000..3265948b2 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionGoal.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestActionGoal_h +#define _ROS_actionlib_TestActionGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TestGoal.h" + +namespace actionlib +{ + + class TestActionGoal : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef actionlib::TestGoal _goal_type; + _goal_type goal; + + TestActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestActionGoal"; }; + virtual const char * getMD5() override { return "348369c5b403676156094e8c159720bf"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionResult.h new file mode 100644 index 000000000..349483361 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestActionResult.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestActionResult_h +#define _ROS_actionlib_TestActionResult_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestResult.h" + +namespace actionlib +{ + + class TestActionResult : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TestResult _result_type; + _result_type result; + + TestActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestActionResult"; }; + virtual const char * getMD5() override { return "3d669e3a63aa986c667ea7b0f46ce85e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestFeedback.h new file mode 100644 index 000000000..536fe7e89 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestFeedback.h @@ -0,0 +1,62 @@ +#ifndef _ROS_actionlib_TestFeedback_h +#define _ROS_actionlib_TestFeedback_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TestFeedback : public ros::Msg + { + public: + typedef int32_t _feedback_type; + _feedback_type feedback; + + TestFeedback(): + feedback(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestFeedback"; }; + virtual const char * getMD5() override { return "49ceb5b32ea3af22073ede4a0328249e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestGoal.h new file mode 100644 index 000000000..959ffc18e --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestGoal.h @@ -0,0 +1,62 @@ +#ifndef _ROS_actionlib_TestGoal_h +#define _ROS_actionlib_TestGoal_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TestGoal : public ros::Msg + { + public: + typedef int32_t _goal_type; + _goal_type goal; + + TestGoal(): + goal(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestGoal"; }; + virtual const char * getMD5() override { return "18df0149936b7aa95588e3862476ebde"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestAction.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestAction.h new file mode 100644 index 000000000..8ae0fec91 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestAction.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestRequestAction_h +#define _ROS_actionlib_TestRequestAction_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib/TestRequestActionGoal.h" +#include "actionlib/TestRequestActionResult.h" +#include "actionlib/TestRequestActionFeedback.h" + +namespace actionlib +{ + + class TestRequestAction : public ros::Msg + { + public: + typedef actionlib::TestRequestActionGoal _action_goal_type; + _action_goal_type action_goal; + typedef actionlib::TestRequestActionResult _action_result_type; + _action_result_type action_result; + typedef actionlib::TestRequestActionFeedback _action_feedback_type; + _action_feedback_type action_feedback; + + TestRequestAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestRequestAction"; }; + virtual const char * getMD5() override { return "dc44b1f4045dbf0d1db54423b3b86b30"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionFeedback.h new file mode 100644 index 000000000..20b43a9e4 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionFeedback.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestRequestActionFeedback_h +#define _ROS_actionlib_TestRequestActionFeedback_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestRequestFeedback.h" + +namespace actionlib +{ + + class TestRequestActionFeedback : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TestRequestFeedback _feedback_type; + _feedback_type feedback; + + TestRequestActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestRequestActionFeedback"; }; + virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionGoal.h new file mode 100644 index 000000000..8f3ca2535 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionGoal.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestRequestActionGoal_h +#define _ROS_actionlib_TestRequestActionGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TestRequestGoal.h" + +namespace actionlib +{ + + class TestRequestActionGoal : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef actionlib::TestRequestGoal _goal_type; + _goal_type goal; + + TestRequestActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestRequestActionGoal"; }; + virtual const char * getMD5() override { return "1889556d3fef88f821c7cb004e4251f3"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionResult.h new file mode 100644 index 000000000..8f487f1fa --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestActionResult.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TestRequestActionResult_h +#define _ROS_actionlib_TestRequestActionResult_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TestRequestResult.h" + +namespace actionlib +{ + + class TestRequestActionResult : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TestRequestResult _result_type; + _result_type result; + + TestRequestActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestRequestActionResult"; }; + virtual const char * getMD5() override { return "0476d1fdf437a3a6e7d6d0e9f5561298"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestFeedback.h new file mode 100644 index 000000000..5e85b6376 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestFeedback.h @@ -0,0 +1,38 @@ +#ifndef _ROS_actionlib_TestRequestFeedback_h +#define _ROS_actionlib_TestRequestFeedback_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TestRequestFeedback : public ros::Msg + { + public: + + TestRequestFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + return offset; + } + + virtual const char * getType() override { return "actionlib/TestRequestFeedback"; }; + virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestGoal.h new file mode 100644 index 000000000..41a1a5d52 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestGoal.h @@ -0,0 +1,215 @@ +#ifndef _ROS_actionlib_TestRequestGoal_h +#define _ROS_actionlib_TestRequestGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "ros/duration.h" + +namespace actionlib +{ + + class TestRequestGoal : public ros::Msg + { + public: + typedef int32_t _terminate_status_type; + _terminate_status_type terminate_status; + typedef bool _ignore_cancel_type; + _ignore_cancel_type ignore_cancel; + typedef const char* _result_text_type; + _result_text_type result_text; + typedef int32_t _the_result_type; + _the_result_type the_result; + typedef bool _is_simple_client_type; + _is_simple_client_type is_simple_client; + typedef ros::Duration _delay_accept_type; + _delay_accept_type delay_accept; + typedef ros::Duration _delay_terminate_type; + _delay_terminate_type delay_terminate; + typedef ros::Duration _pause_status_type; + _pause_status_type pause_status; + enum { TERMINATE_SUCCESS = 0 }; + enum { TERMINATE_ABORTED = 1 }; + enum { TERMINATE_REJECTED = 2 }; + enum { TERMINATE_LOSE = 3 }; + enum { TERMINATE_DROP = 4 }; + enum { TERMINATE_EXCEPTION = 5 }; + + TestRequestGoal(): + terminate_status(0), + ignore_cancel(0), + result_text(""), + the_result(0), + is_simple_client(0), + delay_accept(), + delay_terminate(), + pause_status() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_terminate_status; + u_terminate_status.real = this->terminate_status; + *(outbuffer + offset + 0) = (u_terminate_status.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_terminate_status.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_terminate_status.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_terminate_status.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->terminate_status); + union { + bool real; + uint8_t base; + } u_ignore_cancel; + u_ignore_cancel.real = this->ignore_cancel; + *(outbuffer + offset + 0) = (u_ignore_cancel.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ignore_cancel); + uint32_t length_result_text = strlen(this->result_text); + varToArr(outbuffer + offset, length_result_text); + offset += 4; + memcpy(outbuffer + offset, this->result_text, length_result_text); + offset += length_result_text; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.real = this->the_result; + *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_client; + u_is_simple_client.real = this->is_simple_client; + *(outbuffer + offset + 0) = (u_is_simple_client.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_simple_client); + *(outbuffer + offset + 0) = (this->delay_accept.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_accept.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_accept.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_accept.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_accept.sec); + *(outbuffer + offset + 0) = (this->delay_accept.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_accept.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_accept.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_accept.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_accept.nsec); + *(outbuffer + offset + 0) = (this->delay_terminate.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_terminate.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_terminate.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_terminate.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_terminate.sec); + *(outbuffer + offset + 0) = (this->delay_terminate.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->delay_terminate.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->delay_terminate.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->delay_terminate.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->delay_terminate.nsec); + *(outbuffer + offset + 0) = (this->pause_status.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->pause_status.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->pause_status.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->pause_status.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->pause_status.sec); + *(outbuffer + offset + 0) = (this->pause_status.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->pause_status.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->pause_status.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->pause_status.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->pause_status.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_terminate_status; + u_terminate_status.base = 0; + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->terminate_status = u_terminate_status.real; + offset += sizeof(this->terminate_status); + union { + bool real; + uint8_t base; + } u_ignore_cancel; + u_ignore_cancel.base = 0; + u_ignore_cancel.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ignore_cancel = u_ignore_cancel.real; + offset += sizeof(this->ignore_cancel); + uint32_t length_result_text; + arrToVar(length_result_text, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_result_text; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_result_text-1]=0; + this->result_text = (char *)(inbuffer + offset-1); + offset += length_result_text; + union { + int32_t real; + uint32_t base; + } u_the_result; + u_the_result.base = 0; + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->the_result = u_the_result.real; + offset += sizeof(this->the_result); + union { + bool real; + uint8_t base; + } u_is_simple_client; + u_is_simple_client.base = 0; + u_is_simple_client.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_simple_client = u_is_simple_client.real; + offset += sizeof(this->is_simple_client); + this->delay_accept.sec = ((uint32_t) (*(inbuffer + offset))); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_accept.sec); + this->delay_accept.nsec = ((uint32_t) (*(inbuffer + offset))); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_accept.nsec); + this->delay_terminate.sec = ((uint32_t) (*(inbuffer + offset))); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_terminate.sec); + this->delay_terminate.nsec = ((uint32_t) (*(inbuffer + offset))); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->delay_terminate.nsec); + this->pause_status.sec = ((uint32_t) (*(inbuffer + offset))); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->pause_status.sec); + this->pause_status.nsec = ((uint32_t) (*(inbuffer + offset))); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->pause_status.nsec); + return offset; + } + + virtual const char * getType() override { return "actionlib/TestRequestGoal"; }; + virtual const char * getMD5() override { return "db5d00ba98302d6c6dd3737e9a03ceea"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestResult.h new file mode 100644 index 000000000..f13811f03 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestRequestResult.h @@ -0,0 +1,80 @@ +#ifndef _ROS_actionlib_TestRequestResult_h +#define _ROS_actionlib_TestRequestResult_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TestRequestResult : public ros::Msg + { + public: + typedef int32_t _the_result_type; + _the_result_type the_result; + typedef bool _is_simple_server_type; + _is_simple_server_type is_simple_server; + + TestRequestResult(): + the_result(0), + is_simple_server(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestRequestResult"; }; + virtual const char * getMD5() override { return "61c2364524499c7c5017e2f3fce7ba06"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TestResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestResult.h new file mode 100644 index 000000000..4d3dc17dd --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TestResult.h @@ -0,0 +1,62 @@ +#ifndef _ROS_actionlib_TestResult_h +#define _ROS_actionlib_TestResult_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TestResult : public ros::Msg + { + public: + typedef int32_t _result_type; + _result_type result; + + TestResult(): + result(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TestResult"; }; + virtual const char * getMD5() override { return "034a8e20d6a306665e3a5b340fab3f09"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsAction.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsAction.h new file mode 100644 index 000000000..7e1dfb3ec --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsAction.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TwoIntsAction_h +#define _ROS_actionlib_TwoIntsAction_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib/TwoIntsActionGoal.h" +#include "actionlib/TwoIntsActionResult.h" +#include "actionlib/TwoIntsActionFeedback.h" + +namespace actionlib +{ + + class TwoIntsAction : public ros::Msg + { + public: + typedef actionlib::TwoIntsActionGoal _action_goal_type; + _action_goal_type action_goal; + typedef actionlib::TwoIntsActionResult _action_result_type; + _action_result_type action_result; + typedef actionlib::TwoIntsActionFeedback _action_feedback_type; + _action_feedback_type action_feedback; + + TwoIntsAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TwoIntsAction"; }; + virtual const char * getMD5() override { return "6d1aa538c4bd6183a2dfb7fcac41ee50"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionFeedback.h new file mode 100644 index 000000000..76ecc4fb9 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionFeedback.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TwoIntsActionFeedback_h +#define _ROS_actionlib_TwoIntsActionFeedback_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TwoIntsFeedback.h" + +namespace actionlib +{ + + class TwoIntsActionFeedback : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TwoIntsFeedback _feedback_type; + _feedback_type feedback; + + TwoIntsActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TwoIntsActionFeedback"; }; + virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionGoal.h new file mode 100644 index 000000000..f791b5a09 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionGoal.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TwoIntsActionGoal_h +#define _ROS_actionlib_TwoIntsActionGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib/TwoIntsGoal.h" + +namespace actionlib +{ + + class TwoIntsActionGoal : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef actionlib::TwoIntsGoal _goal_type; + _goal_type goal; + + TwoIntsActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TwoIntsActionGoal"; }; + virtual const char * getMD5() override { return "684a2db55d6ffb8046fb9d6764ce0860"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionResult.h new file mode 100644 index 000000000..74f0ac776 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsActionResult.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_TwoIntsActionResult_h +#define _ROS_actionlib_TwoIntsActionResult_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib/TwoIntsResult.h" + +namespace actionlib +{ + + class TwoIntsActionResult : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib::TwoIntsResult _result_type; + _result_type result; + + TwoIntsActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib/TwoIntsActionResult"; }; + virtual const char * getMD5() override { return "3ba7dea8b8cddcae4528ade4ef74b6e7"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsFeedback.h new file mode 100644 index 000000000..53e624c87 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsFeedback.h @@ -0,0 +1,38 @@ +#ifndef _ROS_actionlib_TwoIntsFeedback_h +#define _ROS_actionlib_TwoIntsFeedback_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsFeedback : public ros::Msg + { + public: + + TwoIntsFeedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + return offset; + } + + virtual const char * getType() override { return "actionlib/TwoIntsFeedback"; }; + virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsGoal.h new file mode 100644 index 000000000..9ca2d8b8b --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsGoal.h @@ -0,0 +1,102 @@ +#ifndef _ROS_actionlib_TwoIntsGoal_h +#define _ROS_actionlib_TwoIntsGoal_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsGoal : public ros::Msg + { + public: + typedef int64_t _a_type; + _a_type a; + typedef int64_t _b_type; + _b_type b; + + TwoIntsGoal(): + a(0), + b(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TwoIntsGoal"; }; + virtual const char * getMD5() override { return "36d09b846be0b371c5f190354dd3153e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsResult.h new file mode 100644 index 000000000..1447bcc7f --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib/TwoIntsResult.h @@ -0,0 +1,70 @@ +#ifndef _ROS_actionlib_TwoIntsResult_h +#define _ROS_actionlib_TwoIntsResult_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib +{ + + class TwoIntsResult : public ros::Msg + { + public: + typedef int64_t _sum_type; + _sum_type sum; + + TwoIntsResult(): + sum(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib/TwoIntsResult"; }; + virtual const char * getMD5() override { return "b88405221c77b1878a3cbbfff53428d7"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalID.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalID.h new file mode 100644 index 000000000..cdf8c55d4 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalID.h @@ -0,0 +1,79 @@ +#ifndef _ROS_actionlib_msgs_GoalID_h +#define _ROS_actionlib_msgs_GoalID_h + +#include +#include +#include +#include "ros/msg.h" +#include "ros/time.h" + +namespace actionlib_msgs +{ + + class GoalID : public ros::Msg + { + public: + typedef ros::Time _stamp_type; + _stamp_type stamp; + typedef const char* _id_type; + _id_type id; + + GoalID(): + stamp(), + id("") + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_id = strlen(this->id); + varToArr(outbuffer + offset, length_id); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_id; + arrToVar(length_id, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + return offset; + } + + virtual const char * getType() override { return "actionlib_msgs/GoalID"; }; + virtual const char * getMD5() override { return "302881f31927c1df708a2dbab0e80ee8"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatus.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatus.h new file mode 100644 index 000000000..49abea359 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatus.h @@ -0,0 +1,78 @@ +#ifndef _ROS_actionlib_msgs_GoalStatus_h +#define _ROS_actionlib_msgs_GoalStatus_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib_msgs/GoalID.h" + +namespace actionlib_msgs +{ + + class GoalStatus : public ros::Msg + { + public: + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef uint8_t _status_type; + _status_type status; + typedef const char* _text_type; + _text_type text; + enum { PENDING = 0 }; + enum { ACTIVE = 1 }; + enum { PREEMPTED = 2 }; + enum { SUCCEEDED = 3 }; + enum { ABORTED = 4 }; + enum { REJECTED = 5 }; + enum { PREEMPTING = 6 }; + enum { RECALLING = 7 }; + enum { RECALLED = 8 }; + enum { LOST = 9 }; + + GoalStatus(): + goal_id(), + status(0), + text("") + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + offset += this->goal_id.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->status >> (8 * 0)) & 0xFF; + offset += sizeof(this->status); + uint32_t length_text = strlen(this->text); + varToArr(outbuffer + offset, length_text); + offset += 4; + memcpy(outbuffer + offset, this->text, length_text); + offset += length_text; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + offset += this->goal_id.deserialize(inbuffer + offset); + this->status = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->status); + uint32_t length_text; + arrToVar(length_text, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_text; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_text-1]=0; + this->text = (char *)(inbuffer + offset-1); + offset += length_text; + return offset; + } + + virtual const char * getType() override { return "actionlib_msgs/GoalStatus"; }; + virtual const char * getMD5() override { return "d388f9b87b3c471f784434d671988d4a"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatusArray.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatusArray.h new file mode 100644 index 000000000..2a96e1cdc --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_msgs/GoalStatusArray.h @@ -0,0 +1,70 @@ +#ifndef _ROS_actionlib_msgs_GoalStatusArray_h +#define _ROS_actionlib_msgs_GoalStatusArray_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" + +namespace actionlib_msgs +{ + + class GoalStatusArray : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + uint32_t status_list_length; + typedef actionlib_msgs::GoalStatus _status_list_type; + _status_list_type st_status_list; + _status_list_type * status_list; + + GoalStatusArray(): + header(), + status_list_length(0), st_status_list(), status_list(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->status_list_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->status_list_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->status_list_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->status_list_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->status_list_length); + for( uint32_t i = 0; i < status_list_length; i++){ + offset += this->status_list[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t status_list_lengthT = ((uint32_t) (*(inbuffer + offset))); + status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + status_list_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->status_list_length); + if(status_list_lengthT > status_list_length) + this->status_list = (actionlib_msgs::GoalStatus*)realloc(this->status_list, status_list_lengthT * sizeof(actionlib_msgs::GoalStatus)); + status_list_length = status_list_lengthT; + for( uint32_t i = 0; i < status_list_length; i++){ + offset += this->st_status_list.deserialize(inbuffer + offset); + memcpy( &(this->status_list[i]), &(this->st_status_list), sizeof(actionlib_msgs::GoalStatus)); + } + return offset; + } + + virtual const char * getType() override { return "actionlib_msgs/GoalStatusArray"; }; + virtual const char * getMD5() override { return "8b2b82f13216d0a8ea88bd3af735e619"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingAction.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingAction.h new file mode 100644 index 000000000..4d3205fe2 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingAction.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_AveragingAction_h +#define _ROS_actionlib_tutorials_AveragingAction_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib_tutorials/AveragingActionGoal.h" +#include "actionlib_tutorials/AveragingActionResult.h" +#include "actionlib_tutorials/AveragingActionFeedback.h" + +namespace actionlib_tutorials +{ + + class AveragingAction : public ros::Msg + { + public: + typedef actionlib_tutorials::AveragingActionGoal _action_goal_type; + _action_goal_type action_goal; + typedef actionlib_tutorials::AveragingActionResult _action_result_type; + _action_result_type action_result; + typedef actionlib_tutorials::AveragingActionFeedback _action_feedback_type; + _action_feedback_type action_feedback; + + AveragingAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingAction"; }; + virtual const char * getMD5() override { return "628678f2b4fa6a5951746a4a2d39e716"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionFeedback.h new file mode 100644 index 000000000..09822471a --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionFeedback.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionFeedback_h +#define _ROS_actionlib_tutorials_AveragingActionFeedback_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/AveragingFeedback.h" + +namespace actionlib_tutorials +{ + + class AveragingActionFeedback : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib_tutorials::AveragingFeedback _feedback_type; + _feedback_type feedback; + + AveragingActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingActionFeedback"; }; + virtual const char * getMD5() override { return "78a4a09241b1791069223ae7ebd5b16b"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionGoal.h new file mode 100644 index 000000000..d70aba172 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionGoal.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionGoal_h +#define _ROS_actionlib_tutorials_AveragingActionGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib_tutorials/AveragingGoal.h" + +namespace actionlib_tutorials +{ + + class AveragingActionGoal : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef actionlib_tutorials::AveragingGoal _goal_type; + _goal_type goal; + + AveragingActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingActionGoal"; }; + virtual const char * getMD5() override { return "1561825b734ebd6039851c501e3fb570"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionResult.h new file mode 100644 index 000000000..5c7270ce4 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingActionResult.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_AveragingActionResult_h +#define _ROS_actionlib_tutorials_AveragingActionResult_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/AveragingResult.h" + +namespace actionlib_tutorials +{ + + class AveragingActionResult : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib_tutorials::AveragingResult _result_type; + _result_type result; + + AveragingActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingActionResult"; }; + virtual const char * getMD5() override { return "8672cb489d347580acdcd05c5d497497"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingFeedback.h new file mode 100644 index 000000000..9d3db9374 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingFeedback.h @@ -0,0 +1,134 @@ +#ifndef _ROS_actionlib_tutorials_AveragingFeedback_h +#define _ROS_actionlib_tutorials_AveragingFeedback_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingFeedback : public ros::Msg + { + public: + typedef int32_t _sample_type; + _sample_type sample; + typedef float _data_type; + _data_type data; + typedef float _mean_type; + _mean_type mean; + typedef float _std_dev_type; + _std_dev_type std_dev; + + AveragingFeedback(): + sample(0), + data(0), + mean(0), + std_dev(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingFeedback"; }; + virtual const char * getMD5() override { return "9e8dfc53c2f2a032ca33fa80ec46fd4f"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingGoal.h new file mode 100644 index 000000000..837d33574 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingGoal.h @@ -0,0 +1,62 @@ +#ifndef _ROS_actionlib_tutorials_AveragingGoal_h +#define _ROS_actionlib_tutorials_AveragingGoal_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingGoal : public ros::Msg + { + public: + typedef int32_t _samples_type; + _samples_type samples; + + AveragingGoal(): + samples(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingGoal"; }; + virtual const char * getMD5() override { return "32c9b10ef9b253faa93b93f564762c8f"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingResult.h new file mode 100644 index 000000000..e8dfa44ef --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/AveragingResult.h @@ -0,0 +1,86 @@ +#ifndef _ROS_actionlib_tutorials_AveragingResult_h +#define _ROS_actionlib_tutorials_AveragingResult_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class AveragingResult : public ros::Msg + { + public: + typedef float _mean_type; + _mean_type mean; + typedef float _std_dev_type; + _std_dev_type std_dev; + + AveragingResult(): + mean(0), + std_dev(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/AveragingResult"; }; + virtual const char * getMD5() override { return "d5c7decf6df75ffb4367a05c1bcc7612"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciAction.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciAction.h new file mode 100644 index 000000000..f9047ba56 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciAction.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciAction_h +#define _ROS_actionlib_tutorials_FibonacciAction_h + +#include +#include +#include +#include "ros/msg.h" +#include "actionlib_tutorials/FibonacciActionGoal.h" +#include "actionlib_tutorials/FibonacciActionResult.h" +#include "actionlib_tutorials/FibonacciActionFeedback.h" + +namespace actionlib_tutorials +{ + + class FibonacciAction : public ros::Msg + { + public: + typedef actionlib_tutorials::FibonacciActionGoal _action_goal_type; + _action_goal_type action_goal; + typedef actionlib_tutorials::FibonacciActionResult _action_result_type; + _action_result_type action_result; + typedef actionlib_tutorials::FibonacciActionFeedback _action_feedback_type; + _action_feedback_type action_feedback; + + FibonacciAction(): + action_goal(), + action_result(), + action_feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciAction"; }; + virtual const char * getMD5() override { return "f59df5767bf7634684781c92598b2406"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h new file mode 100644 index 000000000..8d725673b --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionFeedback.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionFeedback_h +#define _ROS_actionlib_tutorials_FibonacciActionFeedback_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/FibonacciFeedback.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionFeedback : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib_tutorials::FibonacciFeedback _feedback_type; + _feedback_type feedback; + + FibonacciActionFeedback(): + header(), + status(), + feedback() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->feedback.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciActionFeedback"; }; + virtual const char * getMD5() override { return "73b8497a9f629a31c0020900e4148f07"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionGoal.h new file mode 100644 index 000000000..5428d7034 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionGoal.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionGoal_h +#define _ROS_actionlib_tutorials_FibonacciActionGoal_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalID.h" +#include "actionlib_tutorials/FibonacciGoal.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionGoal : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalID _goal_id_type; + _goal_id_type goal_id; + typedef actionlib_tutorials::FibonacciGoal _goal_type; + _goal_type goal; + + FibonacciActionGoal(): + header(), + goal_id(), + goal() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->goal_id.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciActionGoal"; }; + virtual const char * getMD5() override { return "006871c7fa1d0e3d5fe2226bf17b2a94"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionResult.h new file mode 100644 index 000000000..0a3edc69a --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciActionResult.h @@ -0,0 +1,56 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciActionResult_h +#define _ROS_actionlib_tutorials_FibonacciActionResult_h + +#include +#include +#include +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "actionlib_msgs/GoalStatus.h" +#include "actionlib_tutorials/FibonacciResult.h" + +namespace actionlib_tutorials +{ + + class FibonacciActionResult : public ros::Msg + { + public: + typedef std_msgs::Header _header_type; + _header_type header; + typedef actionlib_msgs::GoalStatus _status_type; + _status_type status; + typedef actionlib_tutorials::FibonacciResult _result_type; + _result_type result; + + FibonacciActionResult(): + header(), + status(), + result() + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + offset += this->result.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciActionResult"; }; + virtual const char * getMD5() override { return "bee73a9fe29ae25e966e105f5553dd03"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciFeedback.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciFeedback.h new file mode 100644 index 000000000..ac3af91af --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciFeedback.h @@ -0,0 +1,82 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciFeedback_h +#define _ROS_actionlib_tutorials_FibonacciFeedback_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciFeedback : public ros::Msg + { + public: + uint32_t sequence_length; + typedef int32_t _sequence_type; + _sequence_type st_sequence; + _sequence_type * sequence; + + FibonacciFeedback(): + sequence_length(0), st_sequence(), sequence(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + *(outbuffer + offset + 0) = (this->sequence_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->sequence_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->sequence_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->sequence_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence_length); + for( uint32_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_sequencei; + u_sequencei.real = this->sequence[i]; + *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + uint32_t sequence_lengthT = ((uint32_t) (*(inbuffer + offset))); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->sequence_length); + if(sequence_lengthT > sequence_length) + this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t)); + sequence_length = sequence_lengthT; + for( uint32_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_sequence; + u_st_sequence.base = 0; + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_sequence = u_st_sequence.real; + offset += sizeof(this->st_sequence); + memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t)); + } + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciFeedback"; }; + virtual const char * getMD5() override { return "b81e37d2a31925a0e8ae261a8699cb79"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciGoal.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciGoal.h new file mode 100644 index 000000000..c8dd567ce --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciGoal.h @@ -0,0 +1,62 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciGoal_h +#define _ROS_actionlib_tutorials_FibonacciGoal_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciGoal : public ros::Msg + { + public: + typedef int32_t _order_type; + _order_type order; + + FibonacciGoal(): + order(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + 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) override + { + 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; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciGoal"; }; + virtual const char * getMD5() override { return "6889063349a00b249bd1661df429d822"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciResult.h b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciResult.h new file mode 100644 index 000000000..40c703e6a --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/actionlib_tutorials/FibonacciResult.h @@ -0,0 +1,82 @@ +#ifndef _ROS_actionlib_tutorials_FibonacciResult_h +#define _ROS_actionlib_tutorials_FibonacciResult_h + +#include +#include +#include +#include "ros/msg.h" + +namespace actionlib_tutorials +{ + + class FibonacciResult : public ros::Msg + { + public: + uint32_t sequence_length; + typedef int32_t _sequence_type; + _sequence_type st_sequence; + _sequence_type * sequence; + + FibonacciResult(): + sequence_length(0), st_sequence(), sequence(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + *(outbuffer + offset + 0) = (this->sequence_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->sequence_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->sequence_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->sequence_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence_length); + for( uint32_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_sequencei; + u_sequencei.real = this->sequence[i]; + *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->sequence[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + uint32_t sequence_lengthT = ((uint32_t) (*(inbuffer + offset))); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + sequence_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->sequence_length); + if(sequence_lengthT > sequence_length) + this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t)); + sequence_length = sequence_lengthT; + for( uint32_t i = 0; i < sequence_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_sequence; + u_st_sequence.base = 0; + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_sequence = u_st_sequence.real; + offset += sizeof(this->st_sequence); + memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t)); + } + return offset; + } + + virtual const char * getType() override { return "actionlib_tutorials/FibonacciResult"; }; + virtual const char * getMD5() override { return "b81e37d2a31925a0e8ae261a8699cb79"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/app_manager/App.h b/smart_device_protocol/ros_lib/ros_lib/app_manager/App.h new file mode 100644 index 000000000..5803b7de1 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/app_manager/App.h @@ -0,0 +1,104 @@ +#ifndef _ROS_app_manager_App_h +#define _ROS_app_manager_App_h + +#include +#include +#include +#include "ros/msg.h" +#include "app_manager/Icon.h" +#include "app_manager/ClientApp.h" + +namespace app_manager +{ + + class App : public ros::Msg + { + public: + typedef const char* _name_type; + _name_type name; + typedef const char* _display_name_type; + _display_name_type display_name; + typedef app_manager::Icon _icon_type; + _icon_type icon; + uint32_t client_apps_length; + typedef app_manager::ClientApp _client_apps_type; + _client_apps_type st_client_apps; + _client_apps_type * client_apps; + + App(): + name(""), + display_name(""), + icon(), + client_apps_length(0), st_client_apps(), client_apps(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + uint32_t length_name = strlen(this->name); + varToArr(outbuffer + offset, length_name); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_display_name = strlen(this->display_name); + varToArr(outbuffer + offset, length_display_name); + offset += 4; + memcpy(outbuffer + offset, this->display_name, length_display_name); + offset += length_display_name; + offset += this->icon.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->client_apps_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->client_apps_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->client_apps_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->client_apps_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->client_apps_length); + for( uint32_t i = 0; i < client_apps_length; i++){ + offset += this->client_apps[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + uint32_t length_name; + arrToVar(length_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_display_name; + arrToVar(length_display_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_display_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_display_name-1]=0; + this->display_name = (char *)(inbuffer + offset-1); + offset += length_display_name; + offset += this->icon.deserialize(inbuffer + offset); + uint32_t client_apps_lengthT = ((uint32_t) (*(inbuffer + offset))); + client_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + client_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + client_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->client_apps_length); + if(client_apps_lengthT > client_apps_length) + this->client_apps = (app_manager::ClientApp*)realloc(this->client_apps, client_apps_lengthT * sizeof(app_manager::ClientApp)); + client_apps_length = client_apps_lengthT; + for( uint32_t i = 0; i < client_apps_length; i++){ + offset += this->st_client_apps.deserialize(inbuffer + offset); + memcpy( &(this->client_apps[i]), &(this->st_client_apps), sizeof(app_manager::ClientApp)); + } + return offset; + } + + virtual const char * getType() override { return "app_manager/App"; }; + virtual const char * getMD5() override { return "643c1db5f71b615a47789ff5e190811e"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/app_manager/AppInstallationState.h b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppInstallationState.h new file mode 100644 index 000000000..aedea6141 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppInstallationState.h @@ -0,0 +1,89 @@ +#ifndef _ROS_app_manager_AppInstallationState_h +#define _ROS_app_manager_AppInstallationState_h + +#include +#include +#include +#include "ros/msg.h" +#include "app_manager/ExchangeApp.h" + +namespace app_manager +{ + + class AppInstallationState : public ros::Msg + { + public: + uint32_t installed_apps_length; + typedef app_manager::ExchangeApp _installed_apps_type; + _installed_apps_type st_installed_apps; + _installed_apps_type * installed_apps; + uint32_t available_apps_length; + typedef app_manager::ExchangeApp _available_apps_type; + _available_apps_type st_available_apps; + _available_apps_type * available_apps; + + AppInstallationState(): + installed_apps_length(0), st_installed_apps(), installed_apps(nullptr), + available_apps_length(0), st_available_apps(), available_apps(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + *(outbuffer + offset + 0) = (this->installed_apps_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->installed_apps_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->installed_apps_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->installed_apps_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->installed_apps_length); + for( uint32_t i = 0; i < installed_apps_length; i++){ + offset += this->installed_apps[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->available_apps_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->available_apps_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->available_apps_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->available_apps_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->available_apps_length); + for( uint32_t i = 0; i < available_apps_length; i++){ + offset += this->available_apps[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + uint32_t installed_apps_lengthT = ((uint32_t) (*(inbuffer + offset))); + installed_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + installed_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + installed_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->installed_apps_length); + if(installed_apps_lengthT > installed_apps_length) + this->installed_apps = (app_manager::ExchangeApp*)realloc(this->installed_apps, installed_apps_lengthT * sizeof(app_manager::ExchangeApp)); + installed_apps_length = installed_apps_lengthT; + for( uint32_t i = 0; i < installed_apps_length; i++){ + offset += this->st_installed_apps.deserialize(inbuffer + offset); + memcpy( &(this->installed_apps[i]), &(this->st_installed_apps), sizeof(app_manager::ExchangeApp)); + } + uint32_t available_apps_lengthT = ((uint32_t) (*(inbuffer + offset))); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->available_apps_length); + if(available_apps_lengthT > available_apps_length) + this->available_apps = (app_manager::ExchangeApp*)realloc(this->available_apps, available_apps_lengthT * sizeof(app_manager::ExchangeApp)); + available_apps_length = available_apps_lengthT; + for( uint32_t i = 0; i < available_apps_length; i++){ + offset += this->st_available_apps.deserialize(inbuffer + offset); + memcpy( &(this->available_apps[i]), &(this->st_available_apps), sizeof(app_manager::ExchangeApp)); + } + return offset; + } + + virtual const char * getType() override { return "app_manager/AppInstallationState"; }; + virtual const char * getMD5() override { return "46d45bbda08250199267aff8c0ee8c41"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/app_manager/AppList.h b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppList.h new file mode 100644 index 000000000..9a5a8de66 --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppList.h @@ -0,0 +1,89 @@ +#ifndef _ROS_app_manager_AppList_h +#define _ROS_app_manager_AppList_h + +#include +#include +#include +#include "ros/msg.h" +#include "app_manager/App.h" + +namespace app_manager +{ + + class AppList : public ros::Msg + { + public: + uint32_t running_apps_length; + typedef app_manager::App _running_apps_type; + _running_apps_type st_running_apps; + _running_apps_type * running_apps; + uint32_t available_apps_length; + typedef app_manager::App _available_apps_type; + _available_apps_type st_available_apps; + _available_apps_type * available_apps; + + AppList(): + running_apps_length(0), st_running_apps(), running_apps(nullptr), + available_apps_length(0), st_available_apps(), available_apps(nullptr) + { + } + + virtual int serialize(unsigned char *outbuffer) const override + { + int offset = 0; + *(outbuffer + offset + 0) = (this->running_apps_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->running_apps_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->running_apps_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->running_apps_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->running_apps_length); + for( uint32_t i = 0; i < running_apps_length; i++){ + offset += this->running_apps[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->available_apps_length >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->available_apps_length >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->available_apps_length >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->available_apps_length >> (8 * 3)) & 0xFF; + offset += sizeof(this->available_apps_length); + for( uint32_t i = 0; i < available_apps_length; i++){ + offset += this->available_apps[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) override + { + int offset = 0; + uint32_t running_apps_lengthT = ((uint32_t) (*(inbuffer + offset))); + running_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + running_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + running_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->running_apps_length); + if(running_apps_lengthT > running_apps_length) + this->running_apps = (app_manager::App*)realloc(this->running_apps, running_apps_lengthT * sizeof(app_manager::App)); + running_apps_length = running_apps_lengthT; + for( uint32_t i = 0; i < running_apps_length; i++){ + offset += this->st_running_apps.deserialize(inbuffer + offset); + memcpy( &(this->running_apps[i]), &(this->st_running_apps), sizeof(app_manager::App)); + } + uint32_t available_apps_lengthT = ((uint32_t) (*(inbuffer + offset))); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + available_apps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->available_apps_length); + if(available_apps_lengthT > available_apps_length) + this->available_apps = (app_manager::App*)realloc(this->available_apps, available_apps_lengthT * sizeof(app_manager::App)); + available_apps_length = available_apps_lengthT; + for( uint32_t i = 0; i < available_apps_length; i++){ + offset += this->st_available_apps.deserialize(inbuffer + offset); + memcpy( &(this->available_apps[i]), &(this->st_available_apps), sizeof(app_manager::App)); + } + return offset; + } + + virtual const char * getType() override { return "app_manager/AppList"; }; + virtual const char * getMD5() override { return "8a71ede6bf51909653c7c551f462cb30"; }; + + }; + +} +#endif diff --git a/smart_device_protocol/ros_lib/ros_lib/app_manager/AppStatus.h b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppStatus.h new file mode 100644 index 000000000..c2a4fbaca --- /dev/null +++ b/smart_device_protocol/ros_lib/ros_lib/app_manager/AppStatus.h @@ -0,0 +1,82 @@ +#ifndef _ROS_app_manager_AppStatus_h +#define _ROS_app_manager_AppStatus_h + +#include +#include +#include