├── .gitignore ├── LICENSE ├── README.md ├── SConscript ├── doc ├── README.md ├── ros.gif ├── ros.png └── rosorg.png ├── examples ├── README.md ├── blink.cpp ├── blink_class.cpp ├── button.cpp ├── hello_world_serial.cpp ├── hello_world_tcp.cpp ├── kobuki_control.cpp ├── logging.cpp ├── pubsub.cpp ├── server_client.py ├── service_client.cpp ├── service_server.cpp └── tf.cpp ├── port ├── README.md ├── RTTHardware.h ├── RTTTcpHardware.h ├── Test.h └── ros.h └── src ├── actionlib ├── TestAction.h ├── TestActionFeedback.h ├── TestActionGoal.h ├── TestActionResult.h ├── TestFeedback.h ├── TestGoal.h ├── TestRequestAction.h ├── TestRequestActionFeedback.h ├── TestRequestActionGoal.h ├── TestRequestActionResult.h ├── TestRequestFeedback.h ├── TestRequestGoal.h ├── TestRequestResult.h ├── TestResult.h ├── TwoIntsAction.h ├── TwoIntsActionFeedback.h ├── TwoIntsActionGoal.h ├── TwoIntsActionResult.h ├── TwoIntsFeedback.h ├── TwoIntsGoal.h └── TwoIntsResult.h ├── actionlib_msgs ├── GoalID.h ├── GoalStatus.h └── GoalStatusArray.h ├── bond ├── Constants.h └── Status.h ├── diagnostic_msgs ├── AddDiagnostics.h ├── DiagnosticArray.h ├── DiagnosticStatus.h ├── KeyValue.h └── SelfTest.h ├── duration.cpp ├── dynamic_reconfigure ├── BoolParameter.h ├── Config.h ├── ConfigDescription.h ├── DoubleParameter.h ├── Group.h ├── GroupState.h ├── IntParameter.h ├── ParamDescription.h ├── Reconfigure.h ├── SensorLevels.h └── StrParameter.h ├── examples ├── ADC │ └── ADC.pde ├── Blink │ └── Blink.pde ├── BlinkM │ ├── BlinkM.pde │ └── BlinkM_funcs.h ├── BlinkerWithClass │ └── BlinkerWithClass.ino ├── Clapper │ └── Clapper.pde ├── Esp8266HelloWorld │ └── Esp8266HelloWorld.ino ├── HelloWorld │ └── HelloWorld.pde ├── IrRanger │ └── IrRanger.pde ├── Logging │ └── Logging.pde ├── Odom │ └── Odom.pde ├── ServiceClient │ ├── ServiceClient.pde │ └── client.py ├── ServiceServer │ └── ServiceServer.pde ├── ServoControl │ └── ServoControl.pde ├── TcpBlink │ └── TcpBlink.ino ├── TcpHelloWorld │ └── TcpHelloWorld.ino ├── Temperature │ └── Temperature.pde ├── TimeTF │ └── TimeTF.pde ├── Ultrasound │ └── Ultrasound.pde ├── button_example │ └── button_example.pde └── pubsub │ └── pubsub.pde ├── geometry_msgs ├── Accel.h ├── AccelStamped.h ├── AccelWithCovariance.h ├── AccelWithCovarianceStamped.h ├── Inertia.h ├── InertiaStamped.h ├── Point.h ├── Point32.h ├── PointStamped.h ├── Polygon.h ├── PolygonStamped.h ├── Pose.h ├── Pose2D.h ├── PoseArray.h ├── PoseStamped.h ├── PoseWithCovariance.h ├── PoseWithCovarianceStamped.h ├── Quaternion.h ├── QuaternionStamped.h ├── Transform.h ├── TransformStamped.h ├── Twist.h ├── TwistStamped.h ├── TwistWithCovariance.h ├── TwistWithCovarianceStamped.h ├── Vector3.h ├── Vector3Stamped.h ├── Wrench.h └── WrenchStamped.h ├── nav_msgs ├── GetMap.h ├── GetMapAction.h ├── GetMapActionFeedback.h ├── GetMapActionGoal.h ├── GetMapActionResult.h ├── GetMapFeedback.h ├── GetMapGoal.h ├── GetMapResult.h ├── GetPlan.h ├── GridCells.h ├── LoadMap.h ├── MapMetaData.h ├── OccupancyGrid.h ├── Odometry.h ├── Path.h └── SetMap.h ├── nodelet ├── NodeletList.h ├── NodeletLoad.h └── NodeletUnload.h ├── ros ├── duration.h ├── msg.h ├── node_handle.h ├── publisher.h ├── service_client.h ├── service_server.h ├── subscriber.h └── time.h ├── roscpp ├── Empty.h ├── GetLoggers.h ├── Logger.h └── SetLoggerLevel.h ├── rosgraph_msgs ├── Clock.h ├── Log.h └── TopicStatistics.h ├── rosserial_arduino ├── Adc.h └── Test.h ├── rosserial_msgs ├── Log.h ├── RequestParam.h └── TopicInfo.h ├── sensor_msgs ├── BatteryState.h ├── CameraInfo.h ├── ChannelFloat32.h ├── CompressedImage.h ├── FluidPressure.h ├── Illuminance.h ├── Image.h ├── Imu.h ├── JointState.h ├── Joy.h ├── JoyFeedback.h ├── JoyFeedbackArray.h ├── LaserEcho.h ├── LaserScan.h ├── MagneticField.h ├── MultiDOFJointState.h ├── MultiEchoLaserScan.h ├── NavSatFix.h ├── NavSatStatus.h ├── PointCloud.h ├── PointCloud2.h ├── PointField.h ├── Range.h ├── RegionOfInterest.h ├── RelativeHumidity.h ├── SetCameraInfo.h ├── Temperature.h └── TimeReference.h ├── shape_msgs ├── Mesh.h ├── MeshTriangle.h ├── Plane.h └── SolidPrimitive.h ├── std_msgs ├── Bool.h ├── Byte.h ├── ByteMultiArray.h ├── Char.h ├── ColorRGBA.h ├── Duration.h ├── Empty.h ├── Float32.h ├── Float32MultiArray.h ├── Float64.h ├── Float64MultiArray.h ├── Header.h ├── Int16.h ├── Int16MultiArray.h ├── Int32.h ├── Int32MultiArray.h ├── Int64.h ├── Int64MultiArray.h ├── Int8.h ├── Int8MultiArray.h ├── MultiArrayDimension.h ├── MultiArrayLayout.h ├── String.h ├── Time.h ├── UInt16.h ├── UInt16MultiArray.h ├── UInt32.h ├── UInt32MultiArray.h ├── UInt64.h ├── UInt64MultiArray.h ├── UInt8.h └── UInt8MultiArray.h ├── std_srvs ├── Empty.h ├── SetBool.h └── Trigger.h ├── stereo_msgs └── DisparityImage.h ├── tests ├── array_test │ └── array_test.pde ├── float64_test │ └── float64_test.pde └── time_test │ └── time_test.pde ├── tf ├── FrameGraph.h ├── tf.h ├── tfMessage.h └── transform_broadcaster.h ├── tf2_msgs ├── FrameGraph.h ├── LookupTransformAction.h ├── LookupTransformActionFeedback.h ├── LookupTransformActionGoal.h ├── LookupTransformActionResult.h ├── LookupTransformFeedback.h ├── LookupTransformGoal.h ├── LookupTransformResult.h ├── TF2Error.h └── TFMessage.h ├── time.cpp ├── topic_tools ├── DemuxAdd.h ├── DemuxDelete.h ├── DemuxList.h ├── DemuxSelect.h ├── MuxAdd.h ├── MuxDelete.h ├── MuxList.h └── MuxSelect.h ├── trajectory_msgs ├── JointTrajectory.h ├── JointTrajectoryPoint.h ├── MultiDOFJointTrajectory.h └── MultiDOFJointTrajectoryPoint.h └── visualization_msgs ├── ImageMarker.h ├── InteractiveMarker.h ├── InteractiveMarkerControl.h ├── InteractiveMarkerFeedback.h ├── InteractiveMarkerInit.h ├── InteractiveMarkerPose.h ├── InteractiveMarkerUpdate.h ├── Marker.h ├── MarkerArray.h └── MenuEntry.h /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Object files 5 | *.o 6 | *.ko 7 | *.obj 8 | *.elf 9 | 10 | # Linker output 11 | *.ilk 12 | *.map 13 | *.exp 14 | 15 | # Precompiled Headers 16 | *.gch 17 | *.pch 18 | 19 | # Libraries 20 | *.lib 21 | *.a 22 | *.la 23 | *.lo 24 | 25 | # Shared objects (inc. Windows DLLs) 26 | *.dll 27 | *.so 28 | *.so.* 29 | *.dylib 30 | 31 | # Executables 32 | *.exe 33 | *.out 34 | *.app 35 | *.i*86 36 | *.x86_64 37 | *.hex 38 | 39 | # Debug files 40 | *.dSYM/ 41 | *.su 42 | *.idb 43 | *.pdb 44 | 45 | # Kernel Module Compile Results 46 | *.mod* 47 | *.cmd 48 | .tmp_versions/ 49 | modules.order 50 | Module.symvers 51 | Mkfile.old 52 | dkms.conf 53 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2019, 吴晗 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ![](doc/rosorg.png) 2 | 3 | > 这个分支是 Noetic,其他分支可以查看这里 [Kinetic](https://github.com/wuhanstudio/rt-rosserial/tree/kinetic)/[Melodic](https://github.com/wuhanstudio/rt-rosserial/tree/melodic) 4 | 5 | ### 1. ROS 介绍 6 | **机器人操作系统 ROS** (Robots Operating System) 最早是斯坦福大学的一个软件框架,现在不管是工业机器人,还是娱乐用的机器人都运行着 ROS。 7 | 8 | ![robots](doc/ros.png) 9 | 10 | 一个机器人通常有很多个部件、传感器,为了保证机器人不会因为某一个传感器故障,导致整个系统瘫痪,所以采用了分布式的节点,利用不同节点之间的通讯收集传感器数据和控制指令,这篇文档后面会使用到的通讯协议就是 **rosserial**。 11 | 12 | **rosserial** 可以很方便地让自己的 MCU 用 **USART 有线** 或者 **TCP 无线** 和 ROS 连接,发布传感器信息到 ROS 节点,或者从 ROS 节点订阅传感器信息,例如下面和 ROS 连接后,可以用电脑控制的摄像头小车: 13 | 14 | ![ros car](doc/ros.gif) 15 | 16 | 现在可以选择下面2中通信方式中的一种: 17 | 18 | - UART 19 | - TCP 20 | 21 | 如果使用 TCP 当然要先确保 rt-thread 有网卡设备,并获取到 IP 地址,例如: 22 | 23 | - enc28j60 (SPI) + lwip。 24 | 25 | 26 | ### 2. 使用说明 27 | 28 | #### 2.1 安装 ROS 29 | 30 | 首先需要一个比较强劲的CPU用来运行 ROS 的主节点,例如 PC 或者 ARM ,安装过程可以参照 ROS 的[官网](http://wiki.ros.org/ROS/Installation),现在官方支持最好的还是 Debian 系列。 31 | 32 | 下面以 Ubuntu 安装 **ROS Melodic** 为例: 33 | 34 | 依赖: 35 | 36 | sudo apt install python-rosinstall python-rosinstall-generator python-wstool build-essential 37 | 38 | 安装: 39 | 40 | sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' 41 | sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 42 | sudo apt update 43 | sudo apt install ros-melodic-desktop-full 44 | 45 | 初始化: 46 | 47 | sudo rosdep init 48 | rosdep update 49 | echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc 50 | source ~/.bashrc 51 | 52 | #### 2.2 启动 ROS 53 | 54 | 首先启动一个主节点: 55 | 56 | roscore 57 | 58 | #### 2.3 建立连接 59 | 60 | 如果使用的串口: 61 | 62 | rosrun rosserial_python serial_node.py /dev/ttyUSB0 63 | 64 | 如果使用的 TCP: 65 | 66 | rosrun rosserial_python serial_node.py tcp 67 | 68 | #### 2.4 订阅话题 69 | 70 | 以 hello world 为例: 71 | 72 | rostopic echo /chatter 73 | 74 | 75 | ### 3. 感谢 76 | 77 | - rosserial: https://github.com/ros-drivers/rosserial 78 | 79 | ### 4. 联系方式 80 | 81 | * 维护:Wu Han 82 | * 主页:http://wuhanstudio.cc 83 | * 联系:https://github.com/wuhanstudio/rt-rosserial/issues 84 | -------------------------------------------------------------------------------- /SConscript: -------------------------------------------------------------------------------- 1 | from building import * 2 | import rtconfig 3 | 4 | # get current directory 5 | cwd = GetCurrentDir() 6 | # The set of source files associated with this SConscript file. 7 | src = Glob('src/*.cpp') 8 | 9 | path = [cwd + '/'] 10 | path += [cwd + '/port'] 11 | path += [cwd + '/src'] 12 | 13 | LOCAL_CCFLAGS = '' 14 | 15 | if GetDepend('ROSSERIAL_USING_HELLO_WORLD_UART'): 16 | src += Glob('examples/hello_world_serial.cpp') 17 | 18 | if GetDepend('ROSSERIAL_USING_BLINK_UART'): 19 | src += Glob('examples/blink.cpp') 20 | 21 | if GetDepend('ROSSERIAL_USING_BLINK_CLASS_UART'): 22 | src += Glob('examples/blink_class.cpp') 23 | 24 | if GetDepend('ROSSERIAL_USING_BUTTON_UART'): 25 | src += Glob('examples/button.cpp') 26 | 27 | if GetDepend('ROSSERIAL_USING_PUB_SUB_UART'): 28 | src += Glob('examples/pubsub.cpp') 29 | 30 | if GetDepend('ROSSERIAL_USING_LOGGING_UART'): 31 | src += Glob('examples/logging.cpp') 32 | 33 | if GetDepend('ROSSERIAL_USING_TF_UART'): 34 | src += Glob('examples/tf.cpp') 35 | 36 | if GetDepend('ROSSERIAL_USING_SERVICE_SERVER_UART'): 37 | src += Glob('examples/service_server.cpp') 38 | 39 | if GetDepend('ROSSERIAL_USING_SERVICE_CLIENT_UART'): 40 | src += Glob('examples/service_client.cpp') 41 | 42 | if GetDepend('ROSSERIAL_USING_HELLO_WORLD_TCP'): 43 | src += Glob('examples/hello_world_tcp.cpp') 44 | 45 | if GetDepend('ROSSERIAL_USING_KOBUKI_CONTROL'): 46 | src += Glob('examples/kobuki_control.cpp') 47 | 48 | if rtconfig.CROSS_TOOL == 'gcc': 49 | LOCAL_CCFLAGS += ' -std=c99' 50 | 51 | group = DefineGroup('rosserial', src, depend = ['PKG_USING_ROSSERIAL'], CPPPATH = path, LOCAL_CCFLAGS = LOCAL_CCFLAGS) 52 | 53 | Return('group') 54 | -------------------------------------------------------------------------------- /doc/README.md: -------------------------------------------------------------------------------- 1 | # rt-rosserial 2 | 3 | ## 使用说明 4 | 5 | - 移植请参照 : [移植方法](../port/README.md) 6 | - 例程请参照 : [Example](../examples/README.md) 7 | 8 | ## Todo list 9 | 10 | [●] UART 11 | [  ] TCP 12 | -------------------------------------------------------------------------------- /doc/ros.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wuhanstudio/rt-rosserial/12ceebc6b49a8895a73c96dfc577ba42bcdb6dcd/doc/ros.gif -------------------------------------------------------------------------------- /doc/ros.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wuhanstudio/rt-rosserial/12ceebc6b49a8895a73c96dfc577ba42bcdb6dcd/doc/ros.png -------------------------------------------------------------------------------- /doc/rosorg.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wuhanstudio/rt-rosserial/12ceebc6b49a8895a73c96dfc577ba42bcdb6dcd/doc/rosorg.png -------------------------------------------------------------------------------- /examples/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wuhanstudio/rt-rosserial/12ceebc6b49a8895a73c96dfc577ba42bcdb6dcd/examples/README.md -------------------------------------------------------------------------------- /examples/blink.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Subscriber Example 3 | * Blinks an LED on callback 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #define LED0_PIN GET_PIN(A, 5) 12 | 13 | static ros::NodeHandle nh; 14 | 15 | static void messageCb( const std_msgs::Empty& toggle_msg){ 16 | rt_pin_write(LED0_PIN, PIN_HIGH - rt_pin_read(LED0_PIN)); // blink the led 17 | } 18 | 19 | static ros::Subscriber sub("toggle_led", &messageCb ); 20 | 21 | static void rosserial_blink_thread_entry(void *parameter) 22 | { 23 | rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT); 24 | 25 | nh.initNode(); 26 | nh.subscribe(sub); 27 | 28 | while (1) 29 | { 30 | nh.spinOnce(); 31 | rt_thread_mdelay(500); 32 | } 33 | } 34 | 35 | static void rosserial_blink_example(int argc,char *argv[]) 36 | { 37 | rt_thread_t thread = rt_thread_create("r_blink", rosserial_blink_thread_entry, RT_NULL, 1024, 25, 10); 38 | if(thread != RT_NULL) 39 | { 40 | rt_thread_startup(thread); 41 | rt_kprintf("[rosserial] New thread r_blink\n"); 42 | } 43 | else 44 | { 45 | rt_kprintf("[rosserial] Failed to create thread r_blink\n"); 46 | } 47 | } 48 | MSH_CMD_EXPORT(rosserial_blink_example, roserial blink example with UART); 49 | 50 | // If you are using Keil, you can ignore everything below 51 | 52 | // This is required 53 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 54 | // extern "C" void __cxa_pure_virtual() 55 | // { 56 | // while (1); 57 | //} 58 | 59 | // Moreover, you need to add: 60 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 61 | // in rtconfig.py for arm-none-eabi-gcc 62 | -------------------------------------------------------------------------------- /examples/hello_world_serial.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | static ros::NodeHandle nh; 6 | static std_msgs::String str_msg; 7 | static ros::Publisher chatter("chatter", &str_msg); 8 | 9 | static char hello_msg[13] = "hello world!"; 10 | 11 | static void rosserial_thread_entry(void *parameter) 12 | { 13 | nh.initNode(); 14 | nh.advertise(chatter); 15 | 16 | while (1) 17 | { 18 | if ( nh.connected() ) 19 | { 20 | str_msg.data = hello_msg; 21 | chatter.publish( &str_msg ); 22 | } 23 | /* 24 | else 25 | { 26 | rt_kprintf("[rosserial] Not Connected"); 27 | } 28 | */ 29 | nh.spinOnce(); 30 | rt_thread_delay(RT_TICK_PER_SECOND); 31 | } 32 | } 33 | 34 | static void rosserial_hello_world_serial_example(int argc,char *argv[]) 35 | { 36 | rt_thread_t thread = rt_thread_create("rosserial", rosserial_thread_entry, RT_NULL, 1024, 25, 10); 37 | if(thread != RT_NULL) 38 | { 39 | rt_thread_startup(thread); 40 | rt_kprintf("[rosserial] New thread rosserial\n"); 41 | } 42 | else 43 | { 44 | rt_kprintf("[rosserial] Failed to create thread rosserial\n"); 45 | } 46 | } 47 | MSH_CMD_EXPORT(rosserial_hello_world_serial_example, roserial hello world example with UART); 48 | 49 | 50 | // If you are using Keil, you can ignore everything below 51 | 52 | // This is required 53 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 54 | // extern "C" void __cxa_pure_virtual() 55 | // { 56 | // while (1); 57 | //} 58 | 59 | // Moreover, you need to add: 60 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 61 | // in rtconfig.py for arm-none-eabi-gcc 62 | -------------------------------------------------------------------------------- /examples/hello_world_tcp.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | static ros::NodeHandle nh; 6 | static std_msgs::String str_msg; 7 | static ros::Publisher chatter("chatter", &str_msg); 8 | 9 | static char hello_msg[13] = "hello world!"; 10 | 11 | static void rosserial_thread_entry(void *parameter) 12 | { 13 | // Please make sure you have network connection first 14 | // Set ip address and port 15 | nh.getHardware()->setConnection("192.168.199.100", 11411); 16 | 17 | nh.initNode(); 18 | nh.advertise(chatter); 19 | 20 | while (1) 21 | { 22 | if ( nh.connected() ) 23 | { 24 | str_msg.data = hello_msg; 25 | chatter.publish( &str_msg ); 26 | } 27 | /* 28 | else 29 | { 30 | rt_kprintf("[rosserial] Not Connected \n"); 31 | } 32 | */ 33 | nh.spinOnce(); 34 | rt_thread_delay(RT_TICK_PER_SECOND); 35 | } 36 | } 37 | 38 | static void rosserial_hello_world_tcp_example(int argc,char *argv[]) 39 | { 40 | rt_thread_t thread = rt_thread_create("rosserial", rosserial_thread_entry, RT_NULL, 2048, 25, 10); 41 | if(thread != RT_NULL) 42 | { 43 | rt_thread_startup(thread); 44 | rt_kprintf("[rosserial] New thread rosserial\n"); 45 | } 46 | else 47 | { 48 | rt_kprintf("[rosserial] Failed to create thread rosserial\n"); 49 | } 50 | } 51 | MSH_CMD_EXPORT(rosserial_hello_world_tcp_example, roserial hello world example with TCP); 52 | 53 | 54 | // If you are using Keil, you can ignore everything below 55 | 56 | // This is required 57 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 58 | // extern "C" void __cxa_pure_virtual() 59 | // { 60 | // while (1); 61 | // } 62 | 63 | // Moreover, you need to add: 64 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 65 | // in rtconfig.py for arm-none-eabi-gcc 66 | -------------------------------------------------------------------------------- /examples/kobuki_control.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial kobuki control Example 3 | * Control kobuki robot using teleop 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | static ros::NodeHandle nh; 12 | 13 | static struct kobuki robot; 14 | static double linear_x = 0; 15 | static double angular_z = 0; 16 | 17 | static void kobuki_entry(void *parameter) 18 | { 19 | kobuki_init(&robot); 20 | while(1) 21 | { 22 | rt_thread_mdelay(100); 23 | kobuki_set_speed(linear_x, angular_z); 24 | } 25 | kobuki_close(&robot); 26 | } 27 | 28 | static void messageCb( const geometry_msgs::Twist& twist_msg) 29 | { 30 | rt_kprintf("[rosserial] received control cmd\n"); 31 | linear_x = twist_msg.linear.x; 32 | angular_z = twist_msg.angular.z; 33 | } 34 | 35 | static ros::Subscriber sub("cmd_vel", messageCb ); 36 | 37 | static void rosserial_kobuki_thread_entry(void *parameter) 38 | { 39 | // Please make sure you have network connection first 40 | // Set ip address and port 41 | #if defined ROSSERIAL_USE_TCP 42 | nh.getHardware()->setConnection("192.168.199.100", 11411); 43 | #endif 44 | 45 | nh.initNode(); 46 | nh.subscribe(sub); 47 | while (1) 48 | { 49 | nh.spinOnce(); 50 | rt_thread_mdelay(100); 51 | } 52 | } 53 | 54 | void rosserial_kobuki_control(int argc,char *argv[]) 55 | { 56 | rt_thread_t thread = rt_thread_create("r_kobuki", rosserial_kobuki_thread_entry, RT_NULL, 2048, 15, 10); 57 | if(thread != RT_NULL) 58 | { 59 | rt_thread_startup(thread); 60 | rt_kprintf("[rosserial] New thread r_kobuki\n"); 61 | } 62 | else 63 | { 64 | rt_kprintf("[rosserial] Failed to create thread r_pubsub\n"); 65 | } 66 | 67 | rt_thread_t threadk = rt_thread_create("kobuki", kobuki_entry, RT_NULL, 2048, 10, 10); 68 | if(threadk != RT_NULL) 69 | { 70 | rt_thread_startup(threadk); 71 | rt_kprintf("[micro_ros] New thread kobuki\n"); 72 | } 73 | else 74 | { 75 | rt_kprintf("[micro_ros] Failed to create thread kobuki\n"); 76 | } 77 | } 78 | MSH_CMD_EXPORT(rosserial_kobuki_control, roserial control kobuki); 79 | -------------------------------------------------------------------------------- /examples/logging.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | static ros::NodeHandle nh; 13 | 14 | static std_msgs::String str_msg; 15 | static ros::Publisher chatter("chatter", &str_msg); 16 | 17 | static char hello[13] = "hello world!"; 18 | 19 | static char debug[]= "debug statements"; 20 | static char info[] = "infos"; 21 | static char warn[] = "warnings"; 22 | static char error[] = "errors"; 23 | static char fatal[] = "fatalities"; 24 | 25 | static void rosserial_logging_thread_entry(void *parameter) 26 | { 27 | nh.initNode(); 28 | nh.advertise(chatter); 29 | while (1) 30 | { 31 | str_msg.data = hello; 32 | chatter.publish( &str_msg ); 33 | 34 | nh.logdebug(debug); 35 | nh.loginfo(info); 36 | nh.logwarn(warn); 37 | nh.logerror(error); 38 | nh.logfatal(fatal); 39 | 40 | nh.spinOnce(); 41 | rt_thread_mdelay(500); 42 | } 43 | } 44 | 45 | static void rosserial_logging_example(int argc,char *argv[]) 46 | { 47 | rt_thread_t thread = rt_thread_create("r_log", rosserial_logging_thread_entry, RT_NULL, 1024, 25, 10); 48 | if(thread != RT_NULL) 49 | { 50 | rt_thread_startup(thread); 51 | rt_kprintf("[rosserial] New thread r_log\n"); 52 | } 53 | else 54 | { 55 | rt_kprintf("[rosserial] Failed to create thread r_log\n"); 56 | } 57 | } 58 | MSH_CMD_EXPORT(rosserial_logging_example, roserial publish and subscribe with UART); 59 | 60 | // If you are using Keil, you can ignore everything below 61 | 62 | // This is required 63 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 64 | // extern "C" void __cxa_pure_virtual() 65 | // { 66 | // while (1); 67 | //} 68 | 69 | // Moreover, you need to add: 70 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 71 | // in rtconfig.py for arm-none-eabi-gcc 72 | -------------------------------------------------------------------------------- /examples/pubsub.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | #define LED0_PIN GET_PIN(A, 5) 13 | 14 | static ros::NodeHandle nh; 15 | 16 | static void messageCb( const std_msgs::Empty& toggle_msg){ 17 | rt_pin_write(LED0_PIN, PIN_HIGH - rt_pin_read(LED0_PIN)); // blink the led 18 | } 19 | 20 | static ros::Subscriber sub("toggle_led", messageCb ); 21 | static std_msgs::String str_msg; 22 | static ros::Publisher chatter("chatter", &str_msg); 23 | 24 | static char hello[13] = "hello world!"; 25 | 26 | static void rosserial_pub_sub_thread_entry(void *parameter) 27 | { 28 | rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT); 29 | nh.initNode(); 30 | nh.advertise(chatter); 31 | nh.subscribe(sub); 32 | while (1) 33 | { 34 | str_msg.data = hello; 35 | chatter.publish( &str_msg ); 36 | nh.spinOnce(); 37 | rt_thread_mdelay(500); 38 | } 39 | } 40 | 41 | static void rosserial_pub_sub_example(int argc,char *argv[]) 42 | { 43 | rt_thread_t thread = rt_thread_create("r_pubsub", rosserial_pub_sub_thread_entry, RT_NULL, 1024, 25, 10); 44 | if(thread != RT_NULL) 45 | { 46 | rt_thread_startup(thread); 47 | rt_kprintf("[rosserial] New thread r_pubsub\n"); 48 | } 49 | else 50 | { 51 | rt_kprintf("[rosserial] Failed to create thread r_pubsub\n"); 52 | } 53 | } 54 | MSH_CMD_EXPORT(rosserial_pub_sub_example, roserial publish and subscribe with UART); 55 | 56 | // If you are using Keil, you can ignore everything below 57 | 58 | // This is required 59 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 60 | // extern "C" void __cxa_pure_virtual() 61 | // { 62 | // while (1); 63 | //} 64 | 65 | // Moreover, you need to add: 66 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 67 | // in rtconfig.py for arm-none-eabi-gcc 68 | -------------------------------------------------------------------------------- /examples/server_client.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """ 4 | Sample code to use with ServiceClient.pde 5 | """ 6 | 7 | import roslib; roslib.load_manifest("rosserial_arduino") 8 | import rospy 9 | 10 | from rosserial_arduino.srv import * 11 | 12 | def callback(req): 13 | print "The rt-thread is calling! Please send it a message:" 14 | t = TestResponse() 15 | t.output = raw_input() 16 | return t 17 | 18 | rospy.init_node("service_client_test") 19 | rospy.Service("test_srv", Test, callback) 20 | rospy.spin() 21 | -------------------------------------------------------------------------------- /examples/service_client.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Client 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | #include "port/Test.h" 9 | 10 | static ros::NodeHandle nh; 11 | using rosserial_rtt::Test; 12 | 13 | static ros::ServiceClient client("test_srv"); 14 | 15 | static std_msgs::String str_msg; 16 | static ros::Publisher chatter("chatter", &str_msg); 17 | 18 | static char hello[13] = "hello world!"; 19 | 20 | static void rosserial_client_thread_entry(void *parameter) 21 | { 22 | nh.initNode(); 23 | nh.serviceClient(client); 24 | nh.advertise(chatter); 25 | while(!nh.connected()) nh.spinOnce(); 26 | nh.loginfo("Startup complete"); 27 | 28 | while (1) 29 | { 30 | Test::Request req; 31 | Test::Response res; 32 | req.input = hello; 33 | client.call(req, res); 34 | str_msg.data = res.output; 35 | chatter.publish( &str_msg ); 36 | nh.spinOnce(); 37 | rt_thread_mdelay(10); 38 | } 39 | } 40 | 41 | static void rosserial_client_example(int argc,char *argv[]) 42 | { 43 | rt_thread_t thread = rt_thread_create("r_client", rosserial_client_thread_entry, RT_NULL, 1024, 25, 10); 44 | if(thread != RT_NULL) 45 | { 46 | rt_thread_startup(thread); 47 | rt_kprintf("[rosserial] New thread r_client\n"); 48 | } 49 | else 50 | { 51 | rt_kprintf("[rosserial] Failed to create thread r_client\n"); 52 | } 53 | } 54 | MSH_CMD_EXPORT(rosserial_client_example, roserial publish and subscribe with UART); 55 | 56 | // If you are using Keil, you can ignore everything below 57 | 58 | // This is required 59 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 60 | // extern "C" void __cxa_pure_virtual() 61 | // { 62 | // while (1); 63 | //} 64 | 65 | // Moreover, you need to add: 66 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 67 | // in rtconfig.py for arm-none-eabi-gcc 68 | -------------------------------------------------------------------------------- /examples/service_server.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Server 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | #include "port/Test.h" 9 | 10 | static ros::NodeHandle nh; 11 | 12 | using rosserial_rtt::Test; 13 | 14 | static int i; 15 | static void callback(const Test::Request & req, Test::Response & res){ 16 | if((i++)%2) 17 | { 18 | res.output = "hello"; 19 | } 20 | else 21 | { 22 | res.output = "world"; 23 | } 24 | } 25 | 26 | static ros::ServiceServer server("test_srv", &callback); 27 | 28 | static std_msgs::String str_msg; 29 | static ros::Publisher chatter("chatter", &str_msg); 30 | 31 | static char hello[13] = "hello world!"; 32 | 33 | static void rosserial_server_thread_entry(void *parameter) 34 | { 35 | nh.initNode(); 36 | nh.advertiseService(server); 37 | nh.advertise(chatter); 38 | 39 | while (1) 40 | { 41 | str_msg.data = hello; 42 | chatter.publish( &str_msg ); 43 | nh.spinOnce(); 44 | rt_thread_mdelay(10); 45 | } 46 | } 47 | 48 | static void rosserial_server_example(int argc,char *argv[]) 49 | { 50 | rt_thread_t thread = rt_thread_create("r_server", rosserial_server_thread_entry, RT_NULL, 1024, 25, 10); 51 | if(thread != RT_NULL) 52 | { 53 | rt_thread_startup(thread); 54 | rt_kprintf("[rosserial] New thread r_server\n"); 55 | } 56 | else 57 | { 58 | rt_kprintf("[rosserial] Failed to create thread r_server\n"); 59 | } 60 | } 61 | MSH_CMD_EXPORT(rosserial_server_example, roserial publish and subscribe with UART); 62 | 63 | // If you are using Keil, you can ignore everything below 64 | 65 | // This is required 66 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 67 | // extern "C" void __cxa_pure_virtual() 68 | // { 69 | // while (1); 70 | //} 71 | 72 | // Moreover, you need to add: 73 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 74 | // in rtconfig.py for arm-none-eabi-gcc 75 | -------------------------------------------------------------------------------- /examples/tf.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Time and TF Example 3 | * Publishes a transform at current time 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | ros::NodeHandle nh; 12 | 13 | geometry_msgs::TransformStamped t; 14 | tf::TransformBroadcaster broadcaster; 15 | 16 | char base_link[] = "/base_link"; 17 | char odom[] = "/odom"; 18 | 19 | 20 | static void rosserial_tf_thread_entry(void *parameter) 21 | { 22 | nh.initNode(); 23 | broadcaster.init(nh); 24 | while (1) 25 | { 26 | t.header.frame_id = odom; 27 | t.child_frame_id = base_link; 28 | t.transform.translation.x = 1.0; 29 | t.transform.rotation.x = 0.0; 30 | t.transform.rotation.y = 0.0; 31 | t.transform.rotation.z = 0.0; 32 | t.transform.rotation.w = 1.0; 33 | t.header.stamp = nh.now(); 34 | broadcaster.sendTransform(t); 35 | nh.spinOnce(); 36 | rt_thread_mdelay(10); 37 | } 38 | } 39 | 40 | static void rosserial_tf_example(int argc,char *argv[]) 41 | { 42 | rt_thread_t thread = rt_thread_create("r_tf", rosserial_tf_thread_entry, RT_NULL, 1024, 25, 10); 43 | if(thread != RT_NULL) 44 | { 45 | rt_thread_startup(thread); 46 | rt_kprintf("[rosserial] New thread r_tf\n"); 47 | } 48 | else 49 | { 50 | rt_kprintf("[rosserial] Failed to create thread r_tf\n"); 51 | } 52 | } 53 | MSH_CMD_EXPORT(rosserial_tf_example, roserial publish and subscribe with UART); 54 | 55 | // If you are using Keil, you can ignore everything below 56 | 57 | // This is required 58 | // If you'd like to compile with scons which uses arm-none-eabi-gcc 59 | // extern "C" void __cxa_pure_virtual() 60 | // { 61 | // while (1); 62 | //} 63 | 64 | // Moreover, you need to add: 65 | // CXXFLAGS = CFLAGS + ' -fno-rtti' 66 | // in rtconfig.py for arm-none-eabi-gcc 67 | -------------------------------------------------------------------------------- /port/README.md: -------------------------------------------------------------------------------- 1 | # rosserial 移植 2 | 3 | 移植可以参照官网说明: 4 | 5 | http://wiki.ros.org/rosserial_client/Tutorials/Adding%20Support%20for%20New%20Hardware 6 | 7 | 主要也就是实现这几个函数: 8 | 9 | class Hardware 10 | { 11 | 12 | Hardware(); 13 | 14 | // any initialization code necessary to use the serial port 15 | void init(); 16 | 17 | // read a byte from the serial port. -1 = failure 18 | int read() 19 | 20 | // write data to the connection to ROS 21 | void write(uint8_t* data, int length); 22 | 23 | // returns milliseconds since start of program 24 | unsigned long time(); 25 | 26 | }; -------------------------------------------------------------------------------- /port/ros.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _ROS_H_ 3 | #define _ROS_H_ 4 | 5 | #include "ros/node_handle.h" 6 | 7 | #if defined(ROSSERIAL_USE_TCP) 8 | #include "RTTTcpHardware.h" 9 | #elif defined(ROSSERIAL_USE_SERIAL) 10 | #include "RTTHardware.h" 11 | #endif 12 | 13 | namespace ros 14 | { 15 | #if defined(ROSSERIAL_USE_TCP) 16 | typedef NodeHandle_ NodeHandle; 17 | #elif defined(ROSSERIAL_USE_SERIAL) 18 | typedef NodeHandle_ NodeHandle; 19 | #endif 20 | } 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /src/actionlib/TestAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestAction_h 2 | #define _ROS_actionlib_TestAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib/TestActionGoal.h" 9 | #include "actionlib/TestActionResult.h" 10 | #include "actionlib/TestActionFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestAction : public ros::Msg 16 | { 17 | public: 18 | typedef actionlib::TestActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef actionlib::TestActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef actionlib::TestActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | TestAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->action_goal.serialize(outbuffer + offset); 36 | offset += this->action_result.serialize(outbuffer + offset); 37 | offset += this->action_feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->action_goal.deserialize(inbuffer + offset); 45 | offset += this->action_result.deserialize(inbuffer + offset); 46 | offset += this->action_feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestAction"; }; 51 | virtual const char * getMD5() override { return "991e87a72802262dfbe5d1b3cf6efc9a"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionFeedback_h 2 | #define _ROS_actionlib_TestActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestActionFeedback : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TestFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | TestActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestActionFeedback"; }; 51 | virtual const char * getMD5() override { return "6d3d0bf7fb3dda24779c010a9f3eb7cb"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionGoal_h 2 | #define _ROS_actionlib_TestActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TestGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestActionGoal : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalID _goal_id_type; 21 | _goal_id_type goal_id; 22 | typedef actionlib::TestGoal _goal_type; 23 | _goal_type goal; 24 | 25 | TestActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->goal_id.serialize(outbuffer + offset); 37 | offset += this->goal.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->goal_id.deserialize(inbuffer + offset); 46 | offset += this->goal.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestActionGoal"; }; 51 | virtual const char * getMD5() override { return "348369c5b403676156094e8c159720bf"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionResult_h 2 | #define _ROS_actionlib_TestActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestActionResult : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TestResult _result_type; 23 | _result_type result; 24 | 25 | TestActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->result.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->result.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestActionResult"; }; 51 | virtual const char * getMD5() override { return "3d669e3a63aa986c667ea7b0f46ce85e"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestFeedback_h 2 | #define _ROS_actionlib_TestFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TestFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef int32_t _feedback_type; 16 | _feedback_type feedback; 17 | 18 | TestFeedback(): 19 | feedback(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int32_t real; 28 | uint32_t base; 29 | } u_feedback; 30 | u_feedback.real = this->feedback; 31 | *(outbuffer + offset + 0) = (u_feedback.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_feedback.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_feedback.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_feedback.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->feedback); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | int32_t real; 44 | uint32_t base; 45 | } u_feedback; 46 | u_feedback.base = 0; 47 | u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_feedback.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->feedback = u_feedback.real; 52 | offset += sizeof(this->feedback); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "actionlib/TestFeedback"; }; 57 | virtual const char * getMD5() override { return "49ceb5b32ea3af22073ede4a0328249e"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/actionlib/TestGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestGoal_h 2 | #define _ROS_actionlib_TestGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TestGoal : public ros::Msg 13 | { 14 | public: 15 | typedef int32_t _goal_type; 16 | _goal_type goal; 17 | 18 | TestGoal(): 19 | goal(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int32_t real; 28 | uint32_t base; 29 | } u_goal; 30 | u_goal.real = this->goal; 31 | *(outbuffer + offset + 0) = (u_goal.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_goal.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_goal.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_goal.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->goal); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | int32_t real; 44 | uint32_t base; 45 | } u_goal; 46 | u_goal.base = 0; 47 | u_goal.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_goal.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_goal.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_goal.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->goal = u_goal.real; 52 | offset += sizeof(this->goal); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "actionlib/TestGoal"; }; 57 | virtual const char * getMD5() override { return "18df0149936b7aa95588e3862476ebde"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestAction_h 2 | #define _ROS_actionlib_TestRequestAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib/TestRequestActionGoal.h" 9 | #include "actionlib/TestRequestActionResult.h" 10 | #include "actionlib/TestRequestActionFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestRequestAction : public ros::Msg 16 | { 17 | public: 18 | typedef actionlib::TestRequestActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef actionlib::TestRequestActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef actionlib::TestRequestActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | TestRequestAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->action_goal.serialize(outbuffer + offset); 36 | offset += this->action_result.serialize(outbuffer + offset); 37 | offset += this->action_feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->action_goal.deserialize(inbuffer + offset); 45 | offset += this->action_result.deserialize(inbuffer + offset); 46 | offset += this->action_feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestRequestAction"; }; 51 | virtual const char * getMD5() override { return "dc44b1f4045dbf0d1db54423b3b86b30"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionFeedback_h 2 | #define _ROS_actionlib_TestRequestActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestRequestFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestRequestActionFeedback : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TestRequestFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | TestRequestActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestRequestActionFeedback"; }; 51 | virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionGoal_h 2 | #define _ROS_actionlib_TestRequestActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TestRequestGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestRequestActionGoal : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalID _goal_id_type; 21 | _goal_id_type goal_id; 22 | typedef actionlib::TestRequestGoal _goal_type; 23 | _goal_type goal; 24 | 25 | TestRequestActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->goal_id.serialize(outbuffer + offset); 37 | offset += this->goal.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->goal_id.deserialize(inbuffer + offset); 46 | offset += this->goal.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestRequestActionGoal"; }; 51 | virtual const char * getMD5() override { return "1889556d3fef88f821c7cb004e4251f3"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionResult_h 2 | #define _ROS_actionlib_TestRequestActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestRequestResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TestRequestActionResult : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TestRequestResult _result_type; 23 | _result_type result; 24 | 25 | TestRequestActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->result.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->result.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TestRequestActionResult"; }; 51 | virtual const char * getMD5() override { return "0476d1fdf437a3a6e7d6d0e9f5561298"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestFeedback_h 2 | #define _ROS_actionlib_TestRequestFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TestRequestFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | TestRequestFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "actionlib/TestRequestFeedback"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/actionlib/TestResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestResult_h 2 | #define _ROS_actionlib_TestResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TestResult : public ros::Msg 13 | { 14 | public: 15 | typedef int32_t _result_type; 16 | _result_type result; 17 | 18 | TestResult(): 19 | result(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int32_t real; 28 | uint32_t base; 29 | } u_result; 30 | u_result.real = this->result; 31 | *(outbuffer + offset + 0) = (u_result.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_result.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_result.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_result.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->result); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | int32_t real; 44 | uint32_t base; 45 | } u_result; 46 | u_result.base = 0; 47 | u_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->result = u_result.real; 52 | offset += sizeof(this->result); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "actionlib/TestResult"; }; 57 | virtual const char * getMD5() override { return "034a8e20d6a306665e3a5b340fab3f09"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsAction_h 2 | #define _ROS_actionlib_TwoIntsAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib/TwoIntsActionGoal.h" 9 | #include "actionlib/TwoIntsActionResult.h" 10 | #include "actionlib/TwoIntsActionFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TwoIntsAction : public ros::Msg 16 | { 17 | public: 18 | typedef actionlib::TwoIntsActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef actionlib::TwoIntsActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef actionlib::TwoIntsActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | TwoIntsAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->action_goal.serialize(outbuffer + offset); 36 | offset += this->action_result.serialize(outbuffer + offset); 37 | offset += this->action_feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->action_goal.deserialize(inbuffer + offset); 45 | offset += this->action_result.deserialize(inbuffer + offset); 46 | offset += this->action_feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TwoIntsAction"; }; 51 | virtual const char * getMD5() override { return "6d1aa538c4bd6183a2dfb7fcac41ee50"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionFeedback_h 2 | #define _ROS_actionlib_TwoIntsActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TwoIntsFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TwoIntsActionFeedback : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TwoIntsFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | TwoIntsActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TwoIntsActionFeedback"; }; 51 | virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionGoal_h 2 | #define _ROS_actionlib_TwoIntsActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TwoIntsGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TwoIntsActionGoal : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalID _goal_id_type; 21 | _goal_id_type goal_id; 22 | typedef actionlib::TwoIntsGoal _goal_type; 23 | _goal_type goal; 24 | 25 | TwoIntsActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->goal_id.serialize(outbuffer + offset); 37 | offset += this->goal.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->goal_id.deserialize(inbuffer + offset); 46 | offset += this->goal.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TwoIntsActionGoal"; }; 51 | virtual const char * getMD5() override { return "684a2db55d6ffb8046fb9d6764ce0860"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionResult_h 2 | #define _ROS_actionlib_TwoIntsActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TwoIntsResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | class TwoIntsActionResult : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef actionlib::TwoIntsResult _result_type; 23 | _result_type result; 24 | 25 | TwoIntsActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->result.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->result.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "actionlib/TwoIntsActionResult"; }; 51 | virtual const char * getMD5() override { return "3ba7dea8b8cddcae4528ade4ef74b6e7"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsFeedback_h 2 | #define _ROS_actionlib_TwoIntsFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TwoIntsFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | TwoIntsFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "actionlib/TwoIntsFeedback"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/bond/Constants.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_bond_Constants_h 2 | #define _ROS_bond_Constants_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace bond 10 | { 11 | 12 | class Constants : public ros::Msg 13 | { 14 | public: 15 | enum { DEAD_PUBLISH_PERIOD = 0.05 }; 16 | enum { DEFAULT_CONNECT_TIMEOUT = 10.0 }; 17 | enum { DEFAULT_HEARTBEAT_TIMEOUT = 4.0 }; 18 | enum { DEFAULT_DISCONNECT_TIMEOUT = 2.0 }; 19 | enum { DEFAULT_HEARTBEAT_PERIOD = 1.0 }; 20 | enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout }; 21 | 22 | Constants() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) override 33 | { 34 | int offset = 0; 35 | return offset; 36 | } 37 | 38 | virtual const char * getType() override { return "bond/Constants"; }; 39 | virtual const char * getMD5() override { return "6fc594dc1d7bd7919077042712f8c8b0"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif 45 | -------------------------------------------------------------------------------- /src/diagnostic_msgs/KeyValue.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_diagnostic_msgs_KeyValue_h 2 | #define _ROS_diagnostic_msgs_KeyValue_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace diagnostic_msgs 10 | { 11 | 12 | class KeyValue : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _key_type; 16 | _key_type key; 17 | typedef const char* _value_type; 18 | _value_type value; 19 | 20 | KeyValue(): 21 | key(""), 22 | value("") 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | uint32_t length_key = strlen(this->key); 30 | varToArr(outbuffer + offset, length_key); 31 | offset += 4; 32 | memcpy(outbuffer + offset, this->key, length_key); 33 | offset += length_key; 34 | uint32_t length_value = strlen(this->value); 35 | varToArr(outbuffer + offset, length_value); 36 | offset += 4; 37 | memcpy(outbuffer + offset, this->value, length_value); 38 | offset += length_value; 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) override 43 | { 44 | int offset = 0; 45 | uint32_t length_key; 46 | arrToVar(length_key, (inbuffer + offset)); 47 | offset += 4; 48 | for(unsigned int k= offset; k< offset+length_key; ++k){ 49 | inbuffer[k-1]=inbuffer[k]; 50 | } 51 | inbuffer[offset+length_key-1]=0; 52 | this->key = (char *)(inbuffer + offset-1); 53 | offset += length_key; 54 | uint32_t length_value; 55 | arrToVar(length_value, (inbuffer + offset)); 56 | offset += 4; 57 | for(unsigned int k= offset; k< offset+length_value; ++k){ 58 | inbuffer[k-1]=inbuffer[k]; 59 | } 60 | inbuffer[offset+length_value-1]=0; 61 | this->value = (char *)(inbuffer + offset-1); 62 | offset += length_value; 63 | return offset; 64 | } 65 | 66 | virtual const char * getType() override { return "diagnostic_msgs/KeyValue"; }; 67 | virtual const char * getMD5() override { return "cf57fdc6617a881a88c16e768132149c"; }; 68 | 69 | }; 70 | 71 | } 72 | #endif 73 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/BoolParameter.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_BoolParameter_h 2 | #define _ROS_dynamic_reconfigure_BoolParameter_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | class BoolParameter : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _name_type; 16 | _name_type name; 17 | typedef bool _value_type; 18 | _value_type value; 19 | 20 | BoolParameter(): 21 | name(""), 22 | value(0) 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | uint32_t length_name = strlen(this->name); 30 | varToArr(outbuffer + offset, length_name); 31 | offset += 4; 32 | memcpy(outbuffer + offset, this->name, length_name); 33 | offset += length_name; 34 | union { 35 | bool real; 36 | uint8_t base; 37 | } u_value; 38 | u_value.real = this->value; 39 | *(outbuffer + offset + 0) = (u_value.base >> (8 * 0)) & 0xFF; 40 | offset += sizeof(this->value); 41 | return offset; 42 | } 43 | 44 | virtual int deserialize(unsigned char *inbuffer) override 45 | { 46 | int offset = 0; 47 | uint32_t length_name; 48 | arrToVar(length_name, (inbuffer + offset)); 49 | offset += 4; 50 | for(unsigned int k= offset; k< offset+length_name; ++k){ 51 | inbuffer[k-1]=inbuffer[k]; 52 | } 53 | inbuffer[offset+length_name-1]=0; 54 | this->name = (char *)(inbuffer + offset-1); 55 | offset += length_name; 56 | union { 57 | bool real; 58 | uint8_t base; 59 | } u_value; 60 | u_value.base = 0; 61 | u_value.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 62 | this->value = u_value.real; 63 | offset += sizeof(this->value); 64 | return offset; 65 | } 66 | 67 | virtual const char * getType() override { return "dynamic_reconfigure/BoolParameter"; }; 68 | virtual const char * getMD5() override { return "23f05028c1a699fb83e22401228c3a9e"; }; 69 | 70 | }; 71 | 72 | } 73 | #endif 74 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/DoubleParameter.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_DoubleParameter_h 2 | #define _ROS_dynamic_reconfigure_DoubleParameter_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | class DoubleParameter : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _name_type; 16 | _name_type name; 17 | typedef float _value_type; 18 | _value_type value; 19 | 20 | DoubleParameter(): 21 | name(""), 22 | value(0) 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | uint32_t length_name = strlen(this->name); 30 | varToArr(outbuffer + offset, length_name); 31 | offset += 4; 32 | memcpy(outbuffer + offset, this->name, length_name); 33 | offset += length_name; 34 | offset += serializeAvrFloat64(outbuffer + offset, this->value); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | uint32_t length_name; 42 | arrToVar(length_name, (inbuffer + offset)); 43 | offset += 4; 44 | for(unsigned int k= offset; k< offset+length_name; ++k){ 45 | inbuffer[k-1]=inbuffer[k]; 46 | } 47 | inbuffer[offset+length_name-1]=0; 48 | this->name = (char *)(inbuffer + offset-1); 49 | offset += length_name; 50 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->value)); 51 | return offset; 52 | } 53 | 54 | virtual const char * getType() override { return "dynamic_reconfigure/DoubleParameter"; }; 55 | virtual const char * getMD5() override { return "d8512f27253c0f65f928a67c329cd658"; }; 56 | 57 | }; 58 | 59 | } 60 | #endif 61 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/Reconfigure.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_Reconfigure_h 2 | #define _ROS_SERVICE_Reconfigure_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | #include "dynamic_reconfigure/Config.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | static const char RECONFIGURE[] = "dynamic_reconfigure/Reconfigure"; 13 | 14 | class ReconfigureRequest : public ros::Msg 15 | { 16 | public: 17 | typedef dynamic_reconfigure::Config _config_type; 18 | _config_type config; 19 | 20 | ReconfigureRequest(): 21 | config() 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | offset += this->config.serialize(outbuffer + offset); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) override 33 | { 34 | int offset = 0; 35 | offset += this->config.deserialize(inbuffer + offset); 36 | return offset; 37 | } 38 | 39 | virtual const char * getType() override { return RECONFIGURE; }; 40 | virtual const char * getMD5() override { return "ac41a77620a4a0348b7001641796a8a1"; }; 41 | 42 | }; 43 | 44 | class ReconfigureResponse : public ros::Msg 45 | { 46 | public: 47 | typedef dynamic_reconfigure::Config _config_type; 48 | _config_type config; 49 | 50 | ReconfigureResponse(): 51 | config() 52 | { 53 | } 54 | 55 | virtual int serialize(unsigned char *outbuffer) const override 56 | { 57 | int offset = 0; 58 | offset += this->config.serialize(outbuffer + offset); 59 | return offset; 60 | } 61 | 62 | virtual int deserialize(unsigned char *inbuffer) override 63 | { 64 | int offset = 0; 65 | offset += this->config.deserialize(inbuffer + offset); 66 | return offset; 67 | } 68 | 69 | virtual const char * getType() override { return RECONFIGURE; }; 70 | virtual const char * getMD5() override { return "ac41a77620a4a0348b7001641796a8a1"; }; 71 | 72 | }; 73 | 74 | class Reconfigure { 75 | public: 76 | typedef ReconfigureRequest Request; 77 | typedef ReconfigureResponse Response; 78 | }; 79 | 80 | } 81 | #endif 82 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/SensorLevels.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_SensorLevels_h 2 | #define _ROS_dynamic_reconfigure_SensorLevels_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | class SensorLevels : public ros::Msg 13 | { 14 | public: 15 | enum { RECONFIGURE_CLOSE = 3 }; 16 | enum { RECONFIGURE_STOP = 1 }; 17 | enum { RECONFIGURE_RUNNING = 0 }; 18 | 19 | SensorLevels() 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | return offset; 27 | } 28 | 29 | virtual int deserialize(unsigned char *inbuffer) override 30 | { 31 | int offset = 0; 32 | return offset; 33 | } 34 | 35 | virtual const char * getType() override { return "dynamic_reconfigure/SensorLevels"; }; 36 | virtual const char * getMD5() override { return "6322637bee96d5489db6e2127c47602c"; }; 37 | 38 | }; 39 | 40 | } 41 | #endif 42 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/StrParameter.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_StrParameter_h 2 | #define _ROS_dynamic_reconfigure_StrParameter_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | class StrParameter : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _name_type; 16 | _name_type name; 17 | typedef const char* _value_type; 18 | _value_type value; 19 | 20 | StrParameter(): 21 | name(""), 22 | value("") 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | uint32_t length_name = strlen(this->name); 30 | varToArr(outbuffer + offset, length_name); 31 | offset += 4; 32 | memcpy(outbuffer + offset, this->name, length_name); 33 | offset += length_name; 34 | uint32_t length_value = strlen(this->value); 35 | varToArr(outbuffer + offset, length_value); 36 | offset += 4; 37 | memcpy(outbuffer + offset, this->value, length_value); 38 | offset += length_value; 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) override 43 | { 44 | int offset = 0; 45 | uint32_t length_name; 46 | arrToVar(length_name, (inbuffer + offset)); 47 | offset += 4; 48 | for(unsigned int k= offset; k< offset+length_name; ++k){ 49 | inbuffer[k-1]=inbuffer[k]; 50 | } 51 | inbuffer[offset+length_name-1]=0; 52 | this->name = (char *)(inbuffer + offset-1); 53 | offset += length_name; 54 | uint32_t length_value; 55 | arrToVar(length_value, (inbuffer + offset)); 56 | offset += 4; 57 | for(unsigned int k= offset; k< offset+length_value; ++k){ 58 | inbuffer[k-1]=inbuffer[k]; 59 | } 60 | inbuffer[offset+length_value-1]=0; 61 | this->value = (char *)(inbuffer + offset-1); 62 | offset += length_value; 63 | return offset; 64 | } 65 | 66 | virtual const char * getType() override { return "dynamic_reconfigure/StrParameter"; }; 67 | virtual const char * getMD5() override { return "bc6ccc4a57f61779c8eaae61e9f422e0"; }; 68 | 69 | }; 70 | 71 | } 72 | #endif 73 | -------------------------------------------------------------------------------- /src/examples/ADC/ADC.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial ADC Example 3 | * 4 | * This is a poor man's Oscilloscope. It does not have the sampling 5 | * rate or accuracy of a commerical scope, but it is great to get 6 | * an analog value into ROS in a pinch. 7 | */ 8 | 9 | #if (ARDUINO >= 100) 10 | #include 11 | #else 12 | #include 13 | #endif 14 | #include 15 | #include 16 | 17 | ros::NodeHandle nh; 18 | 19 | rosserial_arduino::Adc adc_msg; 20 | ros::Publisher p("adc", &adc_msg); 21 | 22 | void setup() 23 | { 24 | pinMode(13, OUTPUT); 25 | nh.initNode(); 26 | 27 | nh.advertise(p); 28 | } 29 | 30 | //We average the analog reading to elminate some of the noise 31 | int averageAnalog(int pin){ 32 | int v=0; 33 | for(int i=0; i<4; i++) v+= analogRead(pin); 34 | return v/4; 35 | } 36 | 37 | long adc_timer; 38 | 39 | void loop() 40 | { 41 | adc_msg.adc0 = averageAnalog(0); 42 | adc_msg.adc1 = averageAnalog(1); 43 | adc_msg.adc2 = averageAnalog(2); 44 | adc_msg.adc3 = averageAnalog(3); 45 | adc_msg.adc4 = averageAnalog(4); 46 | adc_msg.adc5 = averageAnalog(5); 47 | 48 | p.publish(&adc_msg); 49 | 50 | nh.spinOnce(); 51 | } 52 | 53 | -------------------------------------------------------------------------------- /src/examples/Blink/Blink.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Subscriber Example 3 | * Blinks an LED on callback 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | 11 | void messageCb( const std_msgs::Empty& toggle_msg){ 12 | digitalWrite(LED_BUILTIN, HIGH-digitalRead(LED_BUILTIN)); // blink the led 13 | } 14 | 15 | ros::Subscriber sub("toggle_led", &messageCb ); 16 | 17 | void setup() 18 | { 19 | pinMode(LED_BUILTIN, OUTPUT); 20 | nh.initNode(); 21 | nh.subscribe(sub); 22 | } 23 | 24 | void loop() 25 | { 26 | nh.spinOnce(); 27 | delay(1); 28 | } 29 | 30 | -------------------------------------------------------------------------------- /src/examples/BlinkerWithClass/BlinkerWithClass.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | ros::NodeHandle nh; 6 | 7 | class Blinker 8 | { 9 | public: 10 | Blinker(byte pin, uint16_t period) 11 | : pin_(pin), period_(period), 12 | subscriber_("set_blink_period", &Blinker::set_period_callback, this), 13 | service_server_("activate_blinker", &Blinker::service_callback, this) 14 | {} 15 | 16 | void init(ros::NodeHandle& nh) 17 | { 18 | pinMode(pin_, OUTPUT); 19 | nh.subscribe(subscriber_); 20 | nh.advertiseService(service_server_); 21 | } 22 | 23 | void run() 24 | { 25 | if(active_ && ((millis() - last_time_) >= period_)) 26 | { 27 | last_time_ = millis(); 28 | digitalWrite(pin_, !digitalRead(pin_)); 29 | } 30 | } 31 | 32 | void set_period_callback(const std_msgs::UInt16& msg) 33 | { 34 | period_ = msg.data; 35 | } 36 | 37 | void service_callback(const std_srvs::SetBool::Request& req, 38 | std_srvs::SetBool::Response& res) 39 | { 40 | active_ = req.data; 41 | res.success = true; 42 | if(req.data) 43 | res.message = "Blinker ON"; 44 | else 45 | res.message = "Blinker OFF"; 46 | } 47 | 48 | private: 49 | const byte pin_; 50 | bool active_ = true; 51 | uint16_t period_; 52 | uint32_t last_time_; 53 | ros::Subscriber subscriber_; 54 | ros::ServiceServer service_server_; 55 | }; 56 | 57 | Blinker blinker(LED_BUILTIN, 500); 58 | 59 | void setup() 60 | { 61 | nh.initNode(); 62 | blinker.init(nh); 63 | } 64 | 65 | void loop() 66 | { 67 | blinker.run(); 68 | nh.spinOnce(); 69 | delay(1); 70 | } 71 | -------------------------------------------------------------------------------- /src/examples/Esp8266HelloWorld/Esp8266HelloWorld.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | * This intend to connect to a Wifi Access Point 5 | * and a rosserial socket server. 6 | * You can launch the rosserial socket server with 7 | * roslaunch rosserial_server socket.launch 8 | * The default port is 11411 9 | * 10 | */ 11 | #include 12 | #include 13 | #include 14 | 15 | const char* ssid = "your-ssid"; 16 | const char* password = "your-password"; 17 | // Set the rosserial socket server IP address 18 | IPAddress server(192,168,1,1); 19 | // Set the rosserial socket server port 20 | const uint16_t serverPort = 11411; 21 | 22 | ros::NodeHandle nh; 23 | // Make a chatter publisher 24 | std_msgs::String str_msg; 25 | ros::Publisher chatter("chatter", &str_msg); 26 | 27 | // Be polite and say hello 28 | char hello[13] = "hello world!"; 29 | 30 | void setup() 31 | { 32 | // Use ESP8266 serial to monitor the process 33 | Serial.begin(115200); 34 | Serial.println(); 35 | Serial.print("Connecting to "); 36 | Serial.println(ssid); 37 | 38 | // Connect the ESP8266 the the wifi AP 39 | WiFi.begin(ssid, password); 40 | while (WiFi.status() != WL_CONNECTED) { 41 | delay(500); 42 | Serial.print("."); 43 | } 44 | Serial.println(""); 45 | Serial.println("WiFi connected"); 46 | Serial.println("IP address: "); 47 | Serial.println(WiFi.localIP()); 48 | 49 | // Set the connection to rosserial socket server 50 | nh.getHardware()->setConnection(server, serverPort); 51 | nh.initNode(); 52 | 53 | // Another way to get IP 54 | Serial.print("IP = "); 55 | Serial.println(nh.getHardware()->getLocalIP()); 56 | 57 | // Start to be polite 58 | nh.advertise(chatter); 59 | } 60 | 61 | void loop() 62 | { 63 | 64 | if (nh.connected()) { 65 | Serial.println("Connected"); 66 | // Say hello 67 | str_msg.data = hello; 68 | chatter.publish( &str_msg ); 69 | } else { 70 | Serial.println("Not Connected"); 71 | } 72 | nh.spinOnce(); 73 | // Loop exproximativly at 1Hz 74 | delay(1000); 75 | } 76 | -------------------------------------------------------------------------------- /src/examples/HelloWorld/HelloWorld.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | 11 | std_msgs::String str_msg; 12 | ros::Publisher chatter("chatter", &str_msg); 13 | 14 | char hello[13] = "hello world!"; 15 | 16 | void setup() 17 | { 18 | nh.initNode(); 19 | nh.advertise(chatter); 20 | } 21 | 22 | void loop() 23 | { 24 | str_msg.data = hello; 25 | chatter.publish( &str_msg ); 26 | nh.spinOnce(); 27 | delay(1000); 28 | } 29 | -------------------------------------------------------------------------------- /src/examples/IrRanger/IrRanger.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial IR Ranger Example 3 | * 4 | * This example is calibrated for the Sharp GP2D120XJ00F. 5 | */ 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | ros::NodeHandle nh; 12 | 13 | 14 | sensor_msgs::Range range_msg; 15 | ros::Publisher pub_range( "range_data", &range_msg); 16 | 17 | const int analog_pin = 0; 18 | unsigned long range_timer; 19 | 20 | /* 21 | * getRange() - samples the analog input from the ranger 22 | * and converts it into meters. 23 | */ 24 | float getRange(int pin_num){ 25 | int sample; 26 | // Get data 27 | sample = analogRead(pin_num)/4; 28 | // if the ADC reading is too low, 29 | // then we are really far away from anything 30 | if(sample < 10) 31 | return 254; // max range 32 | // Magic numbers to get cm 33 | sample= 1309/(sample-3); 34 | return (sample - 1)/100; //convert to meters 35 | } 36 | 37 | char frameid[] = "/ir_ranger"; 38 | 39 | void setup() 40 | { 41 | nh.initNode(); 42 | nh.advertise(pub_range); 43 | 44 | range_msg.radiation_type = sensor_msgs::Range::INFRARED; 45 | range_msg.header.frame_id = frameid; 46 | range_msg.field_of_view = 0.01; 47 | range_msg.min_range = 0.03; 48 | range_msg.max_range = 0.4; 49 | 50 | } 51 | 52 | void loop() 53 | { 54 | // publish the range value every 50 milliseconds 55 | // since it takes that long for the sensor to stabilize 56 | if ( (millis()-range_timer) > 50){ 57 | range_msg.range = getRange(analog_pin); 58 | range_msg.header.stamp = nh.now(); 59 | pub_range.publish(&range_msg); 60 | range_timer = millis() + 50; 61 | } 62 | nh.spinOnce(); 63 | } 64 | 65 | -------------------------------------------------------------------------------- /src/examples/Logging/Logging.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | 13 | std_msgs::String str_msg; 14 | ros::Publisher chatter("chatter", &str_msg); 15 | 16 | char hello[13] = "hello world!"; 17 | 18 | 19 | char debug[]= "debug statements"; 20 | char info[] = "infos"; 21 | char warn[] = "warnings"; 22 | char error[] = "errors"; 23 | char fatal[] = "fatalities"; 24 | 25 | void setup() 26 | { 27 | pinMode(13, OUTPUT); 28 | nh.initNode(); 29 | nh.advertise(chatter); 30 | } 31 | 32 | void loop() 33 | { 34 | str_msg.data = hello; 35 | chatter.publish( &str_msg ); 36 | 37 | nh.logdebug(debug); 38 | nh.loginfo(info); 39 | nh.logwarn(warn); 40 | nh.logerror(error); 41 | nh.logfatal(fatal); 42 | 43 | nh.spinOnce(); 44 | delay(500); 45 | } 46 | -------------------------------------------------------------------------------- /src/examples/Odom/Odom.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Planar Odometry Example 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | geometry_msgs::TransformStamped t; 13 | tf::TransformBroadcaster broadcaster; 14 | 15 | double x = 1.0; 16 | double y = 0.0; 17 | double theta = 1.57; 18 | 19 | char base_link[] = "/base_link"; 20 | char odom[] = "/odom"; 21 | 22 | void setup() 23 | { 24 | nh.initNode(); 25 | broadcaster.init(nh); 26 | } 27 | 28 | void loop() 29 | { 30 | // drive in a circle 31 | double dx = 0.2; 32 | double dtheta = 0.18; 33 | x += cos(theta)*dx*0.1; 34 | y += sin(theta)*dx*0.1; 35 | theta += dtheta*0.1; 36 | if(theta > 3.14) 37 | theta=-3.14; 38 | 39 | // tf odom->base_link 40 | t.header.frame_id = odom; 41 | t.child_frame_id = base_link; 42 | 43 | t.transform.translation.x = x; 44 | t.transform.translation.y = y; 45 | 46 | t.transform.rotation = tf::createQuaternionFromYaw(theta); 47 | t.header.stamp = nh.now(); 48 | 49 | broadcaster.sendTransform(t); 50 | nh.spinOnce(); 51 | 52 | delay(10); 53 | } 54 | -------------------------------------------------------------------------------- /src/examples/ServiceClient/ServiceClient.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Client 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | using rosserial_arduino::Test; 11 | 12 | ros::ServiceClient client("test_srv"); 13 | 14 | std_msgs::String str_msg; 15 | ros::Publisher chatter("chatter", &str_msg); 16 | 17 | char hello[13] = "hello world!"; 18 | 19 | void setup() 20 | { 21 | nh.initNode(); 22 | nh.serviceClient(client); 23 | nh.advertise(chatter); 24 | while(!nh.connected()) nh.spinOnce(); 25 | nh.loginfo("Startup complete"); 26 | } 27 | 28 | void loop() 29 | { 30 | Test::Request req; 31 | Test::Response res; 32 | req.input = hello; 33 | client.call(req, res); 34 | str_msg.data = res.output; 35 | chatter.publish( &str_msg ); 36 | nh.spinOnce(); 37 | delay(100); 38 | } 39 | -------------------------------------------------------------------------------- /src/examples/ServiceClient/client.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """ 4 | Sample code to use with ServiceClient.pde 5 | """ 6 | 7 | import roslib; roslib.load_manifest("rosserial_arduino") 8 | import rospy 9 | 10 | from rosserial_arduino.srv import * 11 | 12 | def callback(req): 13 | print("The arduino is calling! Please send it a message:") 14 | t = TestResponse() 15 | t.output = raw_input() 16 | return t 17 | 18 | rospy.init_node("service_client_test") 19 | rospy.Service("test_srv", Test, callback) 20 | rospy.spin() 21 | -------------------------------------------------------------------------------- /src/examples/ServiceServer/ServiceServer.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Server 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | using rosserial_arduino::Test; 11 | 12 | int i; 13 | void callback(const Test::Request & req, Test::Response & res){ 14 | if((i++)%2) 15 | res.output = "hello"; 16 | else 17 | res.output = "world"; 18 | } 19 | 20 | ros::ServiceServer server("test_srv",&callback); 21 | 22 | std_msgs::String str_msg; 23 | ros::Publisher chatter("chatter", &str_msg); 24 | 25 | char hello[13] = "hello world!"; 26 | 27 | void setup() 28 | { 29 | nh.initNode(); 30 | nh.advertiseService(server); 31 | nh.advertise(chatter); 32 | } 33 | 34 | void loop() 35 | { 36 | str_msg.data = hello; 37 | chatter.publish( &str_msg ); 38 | nh.spinOnce(); 39 | delay(10); 40 | } 41 | -------------------------------------------------------------------------------- /src/examples/ServoControl/ServoControl.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Servo Control Example 3 | * 4 | * This sketch demonstrates the control of hobby R/C servos 5 | * using ROS and the arduiono 6 | * 7 | * For the full tutorial write up, visit 8 | * www.ros.org/wiki/rosserial_arduino_demos 9 | * 10 | * For more information on the Arduino Servo Library 11 | * Checkout : 12 | * http://www.arduino.cc/en/Reference/Servo 13 | */ 14 | 15 | #if (ARDUINO >= 100) 16 | #include 17 | #else 18 | #include 19 | #endif 20 | 21 | #include 22 | #include 23 | #include 24 | 25 | ros::NodeHandle nh; 26 | 27 | Servo servo; 28 | 29 | void servo_cb( const std_msgs::UInt16& cmd_msg){ 30 | servo.write(cmd_msg.data); //set servo angle, should be from 0-180 31 | digitalWrite(13, HIGH-digitalRead(13)); //toggle led 32 | } 33 | 34 | 35 | ros::Subscriber sub("servo", servo_cb); 36 | 37 | void setup(){ 38 | pinMode(13, OUTPUT); 39 | 40 | nh.initNode(); 41 | nh.subscribe(sub); 42 | 43 | servo.attach(9); //attach it to pin 9 44 | } 45 | 46 | void loop(){ 47 | nh.spinOnce(); 48 | delay(1); 49 | } 50 | -------------------------------------------------------------------------------- /src/examples/TcpBlink/TcpBlink.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Subscriber Example using TCP on Arduino Shield (Wiznet W5100 based) 3 | * Blinks an LED on callback 4 | */ 5 | #include 6 | #include 7 | 8 | #define ROSSERIAL_ARDUINO_TCP 9 | 10 | #include 11 | #include 12 | 13 | ros::NodeHandle nh; 14 | 15 | // Shield settings 16 | byte mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; 17 | IPAddress ip(192, 168, 0, 177); 18 | 19 | // Server settings 20 | IPAddress server(192, 168, 0, 11); 21 | uint16_t serverPort = 11411; 22 | 23 | const uint8_t ledPin = 6; // 13 already used for SPI connection with the shield 24 | 25 | void messageCb( const std_msgs::Empty&){ 26 | digitalWrite(ledPin, HIGH-digitalRead(ledPin)); // blink the led 27 | } 28 | 29 | ros::Subscriber sub("toggle_led", &messageCb ); 30 | 31 | void setup() 32 | { 33 | Ethernet.begin(mac, ip); 34 | // give the Ethernet shield a second to initialize: 35 | delay(1000); 36 | pinMode(ledPin, OUTPUT); 37 | nh.getHardware()->setConnection(server, serverPort); 38 | nh.initNode(); 39 | nh.subscribe(sub); 40 | } 41 | 42 | void loop() 43 | { 44 | nh.spinOnce(); 45 | delay(1); 46 | } 47 | 48 | -------------------------------------------------------------------------------- /src/examples/TcpHelloWorld/TcpHelloWorld.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | * This intend to connect to an Arduino Ethernet Shield 5 | * and a rosserial socket server. 6 | * You can launch the rosserial socket server with 7 | * roslaunch rosserial_server socket.launch 8 | * The default port is 11411 9 | * 10 | */ 11 | #include 12 | #include 13 | 14 | // To use the TCP version of rosserial_arduino 15 | #define ROSSERIAL_ARDUINO_TCP 16 | 17 | #include 18 | #include 19 | 20 | // Set the shield settings 21 | byte mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; 22 | IPAddress ip(192, 168, 0, 177); 23 | 24 | // Set the rosserial socket server IP address 25 | IPAddress server(192,168,0,11); 26 | // Set the rosserial socket server port 27 | const uint16_t serverPort = 11411; 28 | 29 | ros::NodeHandle nh; 30 | // Make a chatter publisher 31 | std_msgs::String str_msg; 32 | ros::Publisher chatter("chatter", &str_msg); 33 | 34 | // Be polite and say hello 35 | char hello[13] = "hello world!"; 36 | uint16_t period = 1000; 37 | uint32_t last_time = 0; 38 | 39 | void setup() 40 | { 41 | // Use serial to monitor the process 42 | Serial.begin(115200); 43 | 44 | // Connect the Ethernet 45 | Ethernet.begin(mac, ip); 46 | 47 | // Let some time for the Ethernet Shield to be initialized 48 | delay(1000); 49 | 50 | Serial.println(""); 51 | Serial.println("Ethernet connected"); 52 | Serial.println("IP address: "); 53 | Serial.println(Ethernet.localIP()); 54 | 55 | // Set the connection to rosserial socket server 56 | nh.getHardware()->setConnection(server, serverPort); 57 | nh.initNode(); 58 | 59 | // Another way to get IP 60 | Serial.print("IP = "); 61 | Serial.println(nh.getHardware()->getLocalIP()); 62 | 63 | // Start to be polite 64 | nh.advertise(chatter); 65 | } 66 | 67 | void loop() 68 | { 69 | if(millis() - last_time >= period) 70 | { 71 | last_time = millis(); 72 | if (nh.connected()) 73 | { 74 | Serial.println("Connected"); 75 | // Say hello 76 | str_msg.data = hello; 77 | chatter.publish( &str_msg ); 78 | } else { 79 | Serial.println("Not Connected"); 80 | } 81 | } 82 | nh.spinOnce(); 83 | delay(1); 84 | } 85 | -------------------------------------------------------------------------------- /src/examples/Temperature/Temperature.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Temperature Sensor Example 3 | * 4 | * This tutorial demonstrates the usage of the 5 | * Sparkfun TMP102 Digital Temperature Breakout board 6 | * http://www.sparkfun.com/products/9418 7 | * 8 | * Source Code Based off of: 9 | * http://wiring.org.co/learning/libraries/tmp102sparkfun.html 10 | */ 11 | 12 | #include 13 | #include 14 | #include 15 | 16 | ros::NodeHandle nh; 17 | 18 | 19 | std_msgs::Float32 temp_msg; 20 | ros::Publisher pub_temp("temperature", &temp_msg); 21 | 22 | 23 | // From the datasheet the BMP module address LSB distinguishes 24 | // between read (1) and write (0) operations, corresponding to 25 | // address 0x91 (read) and 0x90 (write). 26 | // shift the address 1 bit right (0x91 or 0x90), the Wire library only needs the 7 27 | // most significant bits for the address 0x91 >> 1 = 0x48 28 | // 0x90 >> 1 = 0x48 (72) 29 | 30 | int sensorAddress = 0x91 >> 1; // From datasheet sensor address is 0x91 31 | // shift the address 1 bit right, the Wire library only needs the 7 32 | // most significant bits for the address 33 | 34 | 35 | void setup() 36 | { 37 | Wire.begin(); // join i2c bus (address optional for master) 38 | 39 | nh.initNode(); 40 | nh.advertise(pub_temp); 41 | 42 | } 43 | 44 | long publisher_timer; 45 | 46 | void loop() 47 | { 48 | 49 | if (millis() > publisher_timer) { 50 | // step 1: request reading from sensor 51 | Wire.requestFrom(sensorAddress,2); 52 | delay(10); 53 | if (2 <= Wire.available()) // if two bytes were received 54 | { 55 | byte msb; 56 | byte lsb; 57 | int temperature; 58 | 59 | msb = Wire.read(); // receive high byte (full degrees) 60 | lsb = Wire.read(); // receive low byte (fraction degrees) 61 | temperature = ((msb) << 4); // MSB 62 | temperature |= (lsb >> 4); // LSB 63 | 64 | temp_msg.data = temperature*0.0625; 65 | pub_temp.publish(&temp_msg); 66 | } 67 | 68 | publisher_timer = millis() + 1000; 69 | } 70 | 71 | nh.spinOnce(); 72 | } 73 | -------------------------------------------------------------------------------- /src/examples/TimeTF/TimeTF.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Time and TF Example 3 | * Publishes a transform at current time 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | geometry_msgs::TransformStamped t; 13 | tf::TransformBroadcaster broadcaster; 14 | 15 | char base_link[] = "/base_link"; 16 | char odom[] = "/odom"; 17 | 18 | void setup() 19 | { 20 | nh.initNode(); 21 | broadcaster.init(nh); 22 | } 23 | 24 | void loop() 25 | { 26 | t.header.frame_id = odom; 27 | t.child_frame_id = base_link; 28 | t.transform.translation.x = 1.0; 29 | t.transform.rotation.x = 0.0; 30 | t.transform.rotation.y = 0.0; 31 | t.transform.rotation.z = 0.0; 32 | t.transform.rotation.w = 1.0; 33 | t.header.stamp = nh.now(); 34 | broadcaster.sendTransform(t); 35 | nh.spinOnce(); 36 | delay(10); 37 | } 38 | -------------------------------------------------------------------------------- /src/examples/Ultrasound/Ultrasound.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Ultrasound Example 3 | * 4 | * This example is for the Maxbotix Ultrasound rangers. 5 | */ 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | ros::NodeHandle nh; 12 | 13 | sensor_msgs::Range range_msg; 14 | ros::Publisher pub_range( "/ultrasound", &range_msg); 15 | 16 | const int adc_pin = 0; 17 | 18 | char frameid[] = "/ultrasound"; 19 | 20 | float getRange_Ultrasound(int pin_num){ 21 | int val = 0; 22 | for(int i=0; i<4; i++) val += analogRead(pin_num); 23 | float range = val; 24 | return range /322.519685; // (0.0124023437 /4) ; //cvt to meters 25 | } 26 | 27 | void setup() 28 | { 29 | nh.initNode(); 30 | nh.advertise(pub_range); 31 | 32 | 33 | range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND; 34 | range_msg.header.frame_id = frameid; 35 | range_msg.field_of_view = 0.1; // fake 36 | range_msg.min_range = 0.0; 37 | range_msg.max_range = 6.47; 38 | 39 | pinMode(8,OUTPUT); 40 | digitalWrite(8, LOW); 41 | } 42 | 43 | 44 | long range_time; 45 | 46 | void loop() 47 | { 48 | 49 | //publish the adc value every 50 milliseconds 50 | //since it takes that long for the sensor to stablize 51 | if ( millis() >= range_time ){ 52 | int r =0; 53 | 54 | range_msg.range = getRange_Ultrasound(5); 55 | range_msg.header.stamp = nh.now(); 56 | pub_range.publish(&range_msg); 57 | range_time = millis() + 50; 58 | } 59 | 60 | nh.spinOnce(); 61 | } 62 | -------------------------------------------------------------------------------- /src/examples/button_example/button_example.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * Button Example for Rosserial 3 | */ 4 | 5 | #include 6 | #include 7 | 8 | 9 | ros::NodeHandle nh; 10 | 11 | std_msgs::Bool pushed_msg; 12 | ros::Publisher pub_button("pushed", &pushed_msg); 13 | 14 | const int button_pin = 7; 15 | const int led_pin = 13; 16 | 17 | bool last_reading; 18 | long last_debounce_time=0; 19 | long debounce_delay=50; 20 | bool published = true; 21 | 22 | void setup() 23 | { 24 | nh.initNode(); 25 | nh.advertise(pub_button); 26 | 27 | //initialize an LED output pin 28 | //and a input pin for our push button 29 | pinMode(led_pin, OUTPUT); 30 | pinMode(button_pin, INPUT); 31 | 32 | //Enable the pullup resistor on the button 33 | digitalWrite(button_pin, HIGH); 34 | 35 | //The button is a normally button 36 | last_reading = ! digitalRead(button_pin); 37 | 38 | } 39 | 40 | void loop() 41 | { 42 | 43 | bool reading = ! digitalRead(button_pin); 44 | 45 | if (last_reading!= reading){ 46 | last_debounce_time = millis(); 47 | published = false; 48 | } 49 | 50 | //if the button value has not changed for the debounce delay, we know its stable 51 | if ( !published && (millis() - last_debounce_time) > debounce_delay) { 52 | digitalWrite(led_pin, reading); 53 | pushed_msg.data = reading; 54 | pub_button.publish(&pushed_msg); 55 | published = true; 56 | } 57 | 58 | last_reading = reading; 59 | 60 | nh.spinOnce(); 61 | } 62 | -------------------------------------------------------------------------------- /src/examples/pubsub/pubsub.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | 13 | void messageCb( const std_msgs::Empty& toggle_msg){ 14 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 15 | } 16 | 17 | ros::Subscriber sub("toggle_led", messageCb ); 18 | 19 | 20 | 21 | std_msgs::String str_msg; 22 | ros::Publisher chatter("chatter", &str_msg); 23 | 24 | char hello[13] = "hello world!"; 25 | 26 | void setup() 27 | { 28 | pinMode(13, OUTPUT); 29 | nh.initNode(); 30 | nh.advertise(chatter); 31 | nh.subscribe(sub); 32 | } 33 | 34 | void loop() 35 | { 36 | str_msg.data = hello; 37 | chatter.publish( &str_msg ); 38 | nh.spinOnce(); 39 | delay(500); 40 | } 41 | -------------------------------------------------------------------------------- /src/geometry_msgs/Accel.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Accel_h 2 | #define _ROS_geometry_msgs_Accel_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Accel : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _linear_type; 17 | _linear_type linear; 18 | typedef geometry_msgs::Vector3 _angular_type; 19 | _angular_type angular; 20 | 21 | Accel(): 22 | linear(), 23 | angular() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const override 28 | { 29 | int offset = 0; 30 | offset += this->linear.serialize(outbuffer + offset); 31 | offset += this->angular.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | offset += this->linear.deserialize(inbuffer + offset); 39 | offset += this->angular.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual const char * getType() override { return "geometry_msgs/Accel"; }; 44 | virtual const char * getMD5() override { return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelStamped_h 2 | #define _ROS_geometry_msgs_AccelStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Accel.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class AccelStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Accel _accel_type; 20 | _accel_type accel; 21 | 22 | AccelStamped(): 23 | header(), 24 | accel() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->accel.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->accel.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/AccelStamped"; }; 45 | virtual const char * getMD5() override { return "d8a98a5d81351b6eb0578c78557e7659"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovariance_h 2 | #define _ROS_geometry_msgs_AccelWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Accel.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class AccelWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Accel _accel_type; 17 | _accel_type accel; 18 | float covariance[36]; 19 | 20 | AccelWithCovariance(): 21 | accel(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | offset += this->accel.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->accel.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | virtual const char * getType() override { return "geometry_msgs/AccelWithCovariance"; }; 47 | virtual const char * getMD5() override { return "ad5a718d699c6be72a02b8d6a139f334"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_AccelWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/AccelWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class AccelWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::AccelWithCovariance _accel_type; 20 | _accel_type accel; 21 | 22 | AccelWithCovarianceStamped(): 23 | header(), 24 | accel() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->accel.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->accel.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/AccelWithCovarianceStamped"; }; 45 | virtual const char * getMD5() override { return "96adb295225031ec8d57fb4251b0a886"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/InertiaStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_InertiaStamped_h 2 | #define _ROS_geometry_msgs_InertiaStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Inertia.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class InertiaStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Inertia _inertia_type; 20 | _inertia_type inertia; 21 | 22 | InertiaStamped(): 23 | header(), 24 | inertia() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->inertia.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->inertia.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/InertiaStamped"; }; 45 | virtual const char * getMD5() override { return "ddee48caeab5a966c5e8d166654a9ac7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Point.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Point_h 2 | #define _ROS_geometry_msgs_Point_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Point : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _z_type; 20 | _z_type z; 21 | 22 | Point(): 23 | x(0), 24 | y(0), 25 | z(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 44 | return offset; 45 | } 46 | 47 | virtual const char * getType() override { return "geometry_msgs/Point"; }; 48 | virtual const char * getMD5() override { return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/geometry_msgs/PointStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PointStamped_h 2 | #define _ROS_geometry_msgs_PointStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Point.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PointStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Point _point_type; 20 | _point_type point; 21 | 22 | PointStamped(): 23 | header(), 24 | point() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->point.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->point.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/PointStamped"; }; 45 | virtual const char * getMD5() override { return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/PolygonStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PolygonStamped_h 2 | #define _ROS_geometry_msgs_PolygonStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Polygon.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PolygonStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Polygon _polygon_type; 20 | _polygon_type polygon; 21 | 22 | PolygonStamped(): 23 | header(), 24 | polygon() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->polygon.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->polygon.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/PolygonStamped"; }; 45 | virtual const char * getMD5() override { return "c6be8f7dc3bee7fe9e8d296070f53340"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Pose.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose_h 2 | #define _ROS_geometry_msgs_Pose_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Point.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Pose : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::Point _position_type; 18 | _position_type position; 19 | typedef geometry_msgs::Quaternion _orientation_type; 20 | _orientation_type orientation; 21 | 22 | Pose(): 23 | position(), 24 | orientation() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->position.serialize(outbuffer + offset); 32 | offset += this->orientation.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->position.deserialize(inbuffer + offset); 40 | offset += this->orientation.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/Pose"; }; 45 | virtual const char * getMD5() override { return "e45d45a5a1ce597b249e23fb30fc871f"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Pose2D.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose2D_h 2 | #define _ROS_geometry_msgs_Pose2D_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Pose2D : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _theta_type; 20 | _theta_type theta; 21 | 22 | Pose2D(): 23 | x(0), 24 | y(0), 25 | theta(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->theta); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->theta)); 44 | return offset; 45 | } 46 | 47 | virtual const char * getType() override { return "geometry_msgs/Pose2D"; }; 48 | virtual const char * getMD5() override { return "938fa65709584ad8e77d238529be13b8"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseStamped_h 2 | #define _ROS_geometry_msgs_PoseStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Pose.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PoseStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Pose _pose_type; 20 | _pose_type pose; 21 | 22 | PoseStamped(): 23 | header(), 24 | pose() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->pose.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->pose.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/PoseStamped"; }; 45 | virtual const char * getMD5() override { return "d3812c3cbc69362b77dc0b19b345f8f5"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovariance_h 2 | #define _ROS_geometry_msgs_PoseWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Pose.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class PoseWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Pose _pose_type; 17 | _pose_type pose; 18 | float covariance[36]; 19 | 20 | PoseWithCovariance(): 21 | pose(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | offset += this->pose.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->pose.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | virtual const char * getType() override { return "geometry_msgs/PoseWithCovariance"; }; 47 | virtual const char * getMD5() override { return "c23e848cf1b7533a8d7c259073a97e6f"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_PoseWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/PoseWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PoseWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::PoseWithCovariance _pose_type; 20 | _pose_type pose; 21 | 22 | PoseWithCovarianceStamped(): 23 | header(), 24 | pose() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->pose.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->pose.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/PoseWithCovarianceStamped"; }; 45 | virtual const char * getMD5() override { return "953b798c0f514ff060a53a3498ce6246"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Quaternion.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Quaternion_h 2 | #define _ROS_geometry_msgs_Quaternion_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Quaternion : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _z_type; 20 | _z_type z; 21 | typedef float _w_type; 22 | _w_type w; 23 | 24 | Quaternion(): 25 | x(0), 26 | y(0), 27 | z(0), 28 | w(0) 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 38 | offset += serializeAvrFloat64(outbuffer + offset, this->w); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) override 43 | { 44 | int offset = 0; 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 46 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 47 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 48 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->w)); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType() override { return "geometry_msgs/Quaternion"; }; 53 | virtual const char * getMD5() override { return "a779879fadf0160734f906b8c19c7004"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/geometry_msgs/QuaternionStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_QuaternionStamped_h 2 | #define _ROS_geometry_msgs_QuaternionStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class QuaternionStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Quaternion _quaternion_type; 20 | _quaternion_type quaternion; 21 | 22 | QuaternionStamped(): 23 | header(), 24 | quaternion() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->quaternion.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->quaternion.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/QuaternionStamped"; }; 45 | virtual const char * getMD5() override { return "e57f1e547e0e1fd13504588ffc8334e2"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Transform.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Transform_h 2 | #define _ROS_geometry_msgs_Transform_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Transform : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::Vector3 _translation_type; 18 | _translation_type translation; 19 | typedef geometry_msgs::Quaternion _rotation_type; 20 | _rotation_type rotation; 21 | 22 | Transform(): 23 | translation(), 24 | rotation() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->translation.serialize(outbuffer + offset); 32 | offset += this->rotation.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->translation.deserialize(inbuffer + offset); 40 | offset += this->rotation.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/Transform"; }; 45 | virtual const char * getMD5() override { return "ac9eff44abf714214112b05d54a3cf9b"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/TransformStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TransformStamped_h 2 | #define _ROS_geometry_msgs_TransformStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Transform.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class TransformStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef const char* _child_frame_id_type; 20 | _child_frame_id_type child_frame_id; 21 | typedef geometry_msgs::Transform _transform_type; 22 | _transform_type transform; 23 | 24 | TransformStamped(): 25 | header(), 26 | child_frame_id(""), 27 | transform() 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const override 32 | { 33 | int offset = 0; 34 | offset += this->header.serialize(outbuffer + offset); 35 | uint32_t length_child_frame_id = strlen(this->child_frame_id); 36 | varToArr(outbuffer + offset, length_child_frame_id); 37 | offset += 4; 38 | memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id); 39 | offset += length_child_frame_id; 40 | offset += this->transform.serialize(outbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual int deserialize(unsigned char *inbuffer) override 45 | { 46 | int offset = 0; 47 | offset += this->header.deserialize(inbuffer + offset); 48 | uint32_t length_child_frame_id; 49 | arrToVar(length_child_frame_id, (inbuffer + offset)); 50 | offset += 4; 51 | for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ 52 | inbuffer[k-1]=inbuffer[k]; 53 | } 54 | inbuffer[offset+length_child_frame_id-1]=0; 55 | this->child_frame_id = (char *)(inbuffer + offset-1); 56 | offset += length_child_frame_id; 57 | offset += this->transform.deserialize(inbuffer + offset); 58 | return offset; 59 | } 60 | 61 | virtual const char * getType() override { return "geometry_msgs/TransformStamped"; }; 62 | virtual const char * getMD5() override { return "b5764a33bfeb3588febc2682852579b0"; }; 63 | 64 | }; 65 | 66 | } 67 | #endif 68 | -------------------------------------------------------------------------------- /src/geometry_msgs/Twist.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Twist_h 2 | #define _ROS_geometry_msgs_Twist_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Twist : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _linear_type; 17 | _linear_type linear; 18 | typedef geometry_msgs::Vector3 _angular_type; 19 | _angular_type angular; 20 | 21 | Twist(): 22 | linear(), 23 | angular() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const override 28 | { 29 | int offset = 0; 30 | offset += this->linear.serialize(outbuffer + offset); 31 | offset += this->angular.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | offset += this->linear.deserialize(inbuffer + offset); 39 | offset += this->angular.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual const char * getType() override { return "geometry_msgs/Twist"; }; 44 | virtual const char * getMD5() override { return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistStamped_h 2 | #define _ROS_geometry_msgs_TwistStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Twist.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class TwistStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Twist _twist_type; 20 | _twist_type twist; 21 | 22 | TwistStamped(): 23 | header(), 24 | twist() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->twist.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->twist.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/TwistStamped"; }; 45 | virtual const char * getMD5() override { return "98d34b0043a2093cf9d9345ab6eef12e"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovariance_h 2 | #define _ROS_geometry_msgs_TwistWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Twist.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class TwistWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Twist _twist_type; 17 | _twist_type twist; 18 | float covariance[36]; 19 | 20 | TwistWithCovariance(): 21 | twist(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | offset += this->twist.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->twist.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | virtual const char * getType() override { return "geometry_msgs/TwistWithCovariance"; }; 47 | virtual const char * getMD5() override { return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_TwistWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/TwistWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class TwistWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::TwistWithCovariance _twist_type; 20 | _twist_type twist; 21 | 22 | TwistWithCovarianceStamped(): 23 | header(), 24 | twist() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->twist.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->twist.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/TwistWithCovarianceStamped"; }; 45 | virtual const char * getMD5() override { return "8927a1a12fb2607ceea095b2dc440a96"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3_h 2 | #define _ROS_geometry_msgs_Vector3_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Vector3 : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _z_type; 20 | _z_type z; 21 | 22 | Vector3(): 23 | x(0), 24 | y(0), 25 | z(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 44 | return offset; 45 | } 46 | 47 | virtual const char * getType() override { return "geometry_msgs/Vector3"; }; 48 | virtual const char * getMD5() override { return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/geometry_msgs/Vector3Stamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3Stamped_h 2 | #define _ROS_geometry_msgs_Vector3Stamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Vector3.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Vector3Stamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Vector3 _vector_type; 20 | _vector_type vector; 21 | 22 | Vector3Stamped(): 23 | header(), 24 | vector() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->vector.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->vector.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/Vector3Stamped"; }; 45 | virtual const char * getMD5() override { return "7b324c7325e683bf02a9b14b01090ec7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/geometry_msgs/Wrench.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Wrench_h 2 | #define _ROS_geometry_msgs_Wrench_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Wrench : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _force_type; 17 | _force_type force; 18 | typedef geometry_msgs::Vector3 _torque_type; 19 | _torque_type torque; 20 | 21 | Wrench(): 22 | force(), 23 | torque() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const override 28 | { 29 | int offset = 0; 30 | offset += this->force.serialize(outbuffer + offset); 31 | offset += this->torque.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | offset += this->force.deserialize(inbuffer + offset); 39 | offset += this->torque.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual const char * getType() override { return "geometry_msgs/Wrench"; }; 44 | virtual const char * getMD5() override { return "4f539cf138b23283b520fd271b567936"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /src/geometry_msgs/WrenchStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_WrenchStamped_h 2 | #define _ROS_geometry_msgs_WrenchStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Wrench.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class WrenchStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Wrench _wrench_type; 20 | _wrench_type wrench; 21 | 22 | WrenchStamped(): 23 | header(), 24 | wrench() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->wrench.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->wrench.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "geometry_msgs/WrenchStamped"; }; 45 | virtual const char * getMD5() override { return "d78d3cb249ce23087ade7e7d0c40cfa7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMap.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_GetMap_h 2 | #define _ROS_SERVICE_GetMap_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | #include "nav_msgs/OccupancyGrid.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | static const char GETMAP[] = "nav_msgs/GetMap"; 13 | 14 | class GetMapRequest : public ros::Msg 15 | { 16 | public: 17 | 18 | GetMapRequest() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType() override { return GETMAP; }; 35 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 36 | 37 | }; 38 | 39 | class GetMapResponse : public ros::Msg 40 | { 41 | public: 42 | typedef nav_msgs::OccupancyGrid _map_type; 43 | _map_type map; 44 | 45 | GetMapResponse(): 46 | map() 47 | { 48 | } 49 | 50 | virtual int serialize(unsigned char *outbuffer) const override 51 | { 52 | int offset = 0; 53 | offset += this->map.serialize(outbuffer + offset); 54 | return offset; 55 | } 56 | 57 | virtual int deserialize(unsigned char *inbuffer) override 58 | { 59 | int offset = 0; 60 | offset += this->map.deserialize(inbuffer + offset); 61 | return offset; 62 | } 63 | 64 | virtual const char * getType() override { return GETMAP; }; 65 | virtual const char * getMD5() override { return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; 66 | 67 | }; 68 | 69 | class GetMap { 70 | public: 71 | typedef GetMapRequest Request; 72 | typedef GetMapResponse Response; 73 | }; 74 | 75 | } 76 | #endif 77 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapAction_h 2 | #define _ROS_nav_msgs_GetMapAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/GetMapActionGoal.h" 9 | #include "nav_msgs/GetMapActionResult.h" 10 | #include "nav_msgs/GetMapActionFeedback.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | class GetMapAction : public ros::Msg 16 | { 17 | public: 18 | typedef nav_msgs::GetMapActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef nav_msgs::GetMapActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef nav_msgs::GetMapActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | GetMapAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->action_goal.serialize(outbuffer + offset); 36 | offset += this->action_result.serialize(outbuffer + offset); 37 | offset += this->action_feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->action_goal.deserialize(inbuffer + offset); 45 | offset += this->action_result.deserialize(inbuffer + offset); 46 | offset += this->action_feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "nav_msgs/GetMapAction"; }; 51 | virtual const char * getMD5() override { return "e611ad23fbf237c031b7536416dc7cd7"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionFeedback_h 2 | #define _ROS_nav_msgs_GetMapActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "nav_msgs/GetMapFeedback.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | class GetMapActionFeedback : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef nav_msgs::GetMapFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | GetMapActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "nav_msgs/GetMapActionFeedback"; }; 51 | virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionGoal_h 2 | #define _ROS_nav_msgs_GetMapActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "nav_msgs/GetMapGoal.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | class GetMapActionGoal : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalID _goal_id_type; 21 | _goal_id_type goal_id; 22 | typedef nav_msgs::GetMapGoal _goal_type; 23 | _goal_type goal; 24 | 25 | GetMapActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->goal_id.serialize(outbuffer + offset); 37 | offset += this->goal.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->goal_id.deserialize(inbuffer + offset); 46 | offset += this->goal.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "nav_msgs/GetMapActionGoal"; }; 51 | virtual const char * getMD5() override { return "4b30be6cd12b9e72826df56b481f40e0"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionResult_h 2 | #define _ROS_nav_msgs_GetMapActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "nav_msgs/GetMapResult.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | class GetMapActionResult : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef nav_msgs::GetMapResult _result_type; 23 | _result_type result; 24 | 25 | GetMapActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->result.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->result.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "nav_msgs/GetMapActionResult"; }; 51 | virtual const char * getMD5() override { return "ac66e5b9a79bb4bbd33dab245236c892"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapFeedback_h 2 | #define _ROS_nav_msgs_GetMapFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | class GetMapFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | GetMapFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "nav_msgs/GetMapFeedback"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapGoal_h 2 | #define _ROS_nav_msgs_GetMapGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | class GetMapGoal : public ros::Msg 13 | { 14 | public: 15 | 16 | GetMapGoal() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "nav_msgs/GetMapGoal"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapResult_h 2 | #define _ROS_nav_msgs_GetMapResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/OccupancyGrid.h" 9 | 10 | namespace nav_msgs 11 | { 12 | 13 | class GetMapResult : public ros::Msg 14 | { 15 | public: 16 | typedef nav_msgs::OccupancyGrid _map_type; 17 | _map_type map; 18 | 19 | GetMapResult(): 20 | map() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | offset += this->map.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) override 32 | { 33 | int offset = 0; 34 | offset += this->map.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual const char * getType() override { return "nav_msgs/GetMapResult"; }; 39 | virtual const char * getMD5() override { return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif 45 | -------------------------------------------------------------------------------- /src/roscpp/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_Empty_h 2 | #define _ROS_SERVICE_Empty_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace roscpp 9 | { 10 | 11 | static const char EMPTY[] = "roscpp/Empty"; 12 | 13 | class EmptyRequest : public ros::Msg 14 | { 15 | public: 16 | 17 | EmptyRequest() 18 | { 19 | } 20 | 21 | virtual int serialize(unsigned char *outbuffer) const override 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) override 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | virtual const char * getType() override { return EMPTY; }; 34 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 35 | 36 | }; 37 | 38 | class EmptyResponse : public ros::Msg 39 | { 40 | public: 41 | 42 | EmptyResponse() 43 | { 44 | } 45 | 46 | virtual int serialize(unsigned char *outbuffer) const override 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) override 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | virtual const char * getType() override { return EMPTY; }; 59 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /src/roscpp/Logger.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_roscpp_Logger_h 2 | #define _ROS_roscpp_Logger_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace roscpp 10 | { 11 | 12 | class Logger : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _name_type; 16 | _name_type name; 17 | typedef const char* _level_type; 18 | _level_type level; 19 | 20 | Logger(): 21 | name(""), 22 | level("") 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | uint32_t length_name = strlen(this->name); 30 | varToArr(outbuffer + offset, length_name); 31 | offset += 4; 32 | memcpy(outbuffer + offset, this->name, length_name); 33 | offset += length_name; 34 | uint32_t length_level = strlen(this->level); 35 | varToArr(outbuffer + offset, length_level); 36 | offset += 4; 37 | memcpy(outbuffer + offset, this->level, length_level); 38 | offset += length_level; 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) override 43 | { 44 | int offset = 0; 45 | uint32_t length_name; 46 | arrToVar(length_name, (inbuffer + offset)); 47 | offset += 4; 48 | for(unsigned int k= offset; k< offset+length_name; ++k){ 49 | inbuffer[k-1]=inbuffer[k]; 50 | } 51 | inbuffer[offset+length_name-1]=0; 52 | this->name = (char *)(inbuffer + offset-1); 53 | offset += length_name; 54 | uint32_t length_level; 55 | arrToVar(length_level, (inbuffer + offset)); 56 | offset += 4; 57 | for(unsigned int k= offset; k< offset+length_level; ++k){ 58 | inbuffer[k-1]=inbuffer[k]; 59 | } 60 | inbuffer[offset+length_level-1]=0; 61 | this->level = (char *)(inbuffer + offset-1); 62 | offset += length_level; 63 | return offset; 64 | } 65 | 66 | virtual const char * getType() override { return "roscpp/Logger"; }; 67 | virtual const char * getMD5() override { return "a6069a2ff40db7bd32143dd66e1f408e"; }; 68 | 69 | }; 70 | 71 | } 72 | #endif 73 | -------------------------------------------------------------------------------- /src/rosgraph_msgs/Clock.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rosgraph_msgs_Clock_h 2 | #define _ROS_rosgraph_msgs_Clock_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "ros/time.h" 9 | 10 | namespace rosgraph_msgs 11 | { 12 | 13 | class Clock : public ros::Msg 14 | { 15 | public: 16 | typedef ros::Time _clock_type; 17 | _clock_type clock; 18 | 19 | Clock(): 20 | clock() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | *(outbuffer + offset + 0) = (this->clock.sec >> (8 * 0)) & 0xFF; 28 | *(outbuffer + offset + 1) = (this->clock.sec >> (8 * 1)) & 0xFF; 29 | *(outbuffer + offset + 2) = (this->clock.sec >> (8 * 2)) & 0xFF; 30 | *(outbuffer + offset + 3) = (this->clock.sec >> (8 * 3)) & 0xFF; 31 | offset += sizeof(this->clock.sec); 32 | *(outbuffer + offset + 0) = (this->clock.nsec >> (8 * 0)) & 0xFF; 33 | *(outbuffer + offset + 1) = (this->clock.nsec >> (8 * 1)) & 0xFF; 34 | *(outbuffer + offset + 2) = (this->clock.nsec >> (8 * 2)) & 0xFF; 35 | *(outbuffer + offset + 3) = (this->clock.nsec >> (8 * 3)) & 0xFF; 36 | offset += sizeof(this->clock.nsec); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) override 41 | { 42 | int offset = 0; 43 | this->clock.sec = ((uint32_t) (*(inbuffer + offset))); 44 | this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 45 | this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 46 | this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 47 | offset += sizeof(this->clock.sec); 48 | this->clock.nsec = ((uint32_t) (*(inbuffer + offset))); 49 | this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 50 | this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 51 | this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 52 | offset += sizeof(this->clock.nsec); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "rosgraph_msgs/Clock"; }; 57 | virtual const char * getMD5() override { return "a9c97c1d230cfc112e270351a944ee47"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/rosserial_msgs/Log.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rosserial_msgs_Log_h 2 | #define _ROS_rosserial_msgs_Log_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace rosserial_msgs 10 | { 11 | 12 | class Log : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _level_type; 16 | _level_type level; 17 | typedef const char* _msg_type; 18 | _msg_type msg; 19 | enum { ROSDEBUG = 0 }; 20 | enum { INFO = 1 }; 21 | enum { WARN = 2 }; 22 | enum { ERROR = 3 }; 23 | enum { FATAL = 4 }; 24 | 25 | Log(): 26 | level(0), 27 | msg("") 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const 32 | { 33 | int offset = 0; 34 | *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF; 35 | offset += sizeof(this->level); 36 | uint32_t length_msg = strlen(this->msg); 37 | varToArr(outbuffer + offset, length_msg); 38 | offset += 4; 39 | memcpy(outbuffer + offset, this->msg, length_msg); 40 | offset += length_msg; 41 | return offset; 42 | } 43 | 44 | virtual int deserialize(unsigned char *inbuffer) 45 | { 46 | int offset = 0; 47 | this->level = ((uint8_t) (*(inbuffer + offset))); 48 | offset += sizeof(this->level); 49 | uint32_t length_msg; 50 | arrToVar(length_msg, (inbuffer + offset)); 51 | offset += 4; 52 | for(unsigned int k= offset; k< offset+length_msg; ++k){ 53 | inbuffer[k-1]=inbuffer[k]; 54 | } 55 | inbuffer[offset+length_msg-1]=0; 56 | this->msg = (char *)(inbuffer + offset-1); 57 | offset += length_msg; 58 | return offset; 59 | } 60 | 61 | virtual const char * getType() { return "rosserial_msgs/Log"; }; 62 | virtual const char * getMD5() { return "11abd731c25933261cd6183bd12d6295"; }; 63 | 64 | }; 65 | 66 | } 67 | #endif 68 | -------------------------------------------------------------------------------- /src/sensor_msgs/FluidPressure.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_FluidPressure_h 2 | #define _ROS_sensor_msgs_FluidPressure_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | class FluidPressure : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef float _fluid_pressure_type; 19 | _fluid_pressure_type fluid_pressure; 20 | typedef float _variance_type; 21 | _variance_type variance; 22 | 23 | FluidPressure(): 24 | header(), 25 | fluid_pressure(0), 26 | variance(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->fluid_pressure); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | offset += this->header.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->fluid_pressure)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 45 | return offset; 46 | } 47 | 48 | virtual const char * getType() override { return "sensor_msgs/FluidPressure"; }; 49 | virtual const char * getMD5() override { return "804dc5cea1c5306d6a2eb80b9833befe"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/sensor_msgs/Illuminance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_Illuminance_h 2 | #define _ROS_sensor_msgs_Illuminance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | class Illuminance : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef float _illuminance_type; 19 | _illuminance_type illuminance; 20 | typedef float _variance_type; 21 | _variance_type variance; 22 | 23 | Illuminance(): 24 | header(), 25 | illuminance(0), 26 | variance(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->illuminance); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | offset += this->header.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->illuminance)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 45 | return offset; 46 | } 47 | 48 | virtual const char * getType() override { return "sensor_msgs/Illuminance"; }; 49 | virtual const char * getMD5() override { return "8cf5febb0952fca9d650c3d11a81a188"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/sensor_msgs/MagneticField.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_MagneticField_h 2 | #define _ROS_sensor_msgs_MagneticField_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Vector3.h" 10 | 11 | namespace sensor_msgs 12 | { 13 | 14 | class MagneticField : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Vector3 _magnetic_field_type; 20 | _magnetic_field_type magnetic_field; 21 | float magnetic_field_covariance[9]; 22 | 23 | MagneticField(): 24 | header(), 25 | magnetic_field(), 26 | magnetic_field_covariance() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->magnetic_field.serialize(outbuffer + offset); 35 | for( uint32_t i = 0; i < 9; i++){ 36 | offset += serializeAvrFloat64(outbuffer + offset, this->magnetic_field_covariance[i]); 37 | } 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->magnetic_field.deserialize(inbuffer + offset); 46 | for( uint32_t i = 0; i < 9; i++){ 47 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->magnetic_field_covariance[i])); 48 | } 49 | return offset; 50 | } 51 | 52 | virtual const char * getType() override { return "sensor_msgs/MagneticField"; }; 53 | virtual const char * getMD5() override { return "2f3b0b43eed0c9501de0fa3ff89a45aa"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/sensor_msgs/NavSatStatus.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_NavSatStatus_h 2 | #define _ROS_sensor_msgs_NavSatStatus_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace sensor_msgs 10 | { 11 | 12 | class NavSatStatus : public ros::Msg 13 | { 14 | public: 15 | typedef int8_t _status_type; 16 | _status_type status; 17 | typedef uint16_t _service_type; 18 | _service_type service; 19 | enum { STATUS_NO_FIX = -1 }; 20 | enum { STATUS_FIX = 0 }; 21 | enum { STATUS_SBAS_FIX = 1 }; 22 | enum { STATUS_GBAS_FIX = 2 }; 23 | enum { SERVICE_GPS = 1 }; 24 | enum { SERVICE_GLONASS = 2 }; 25 | enum { SERVICE_COMPASS = 4 }; 26 | enum { SERVICE_GALILEO = 8 }; 27 | 28 | NavSatStatus(): 29 | status(0), 30 | service(0) 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | union { 38 | int8_t real; 39 | uint8_t base; 40 | } u_status; 41 | u_status.real = this->status; 42 | *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF; 43 | offset += sizeof(this->status); 44 | *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF; 45 | *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF; 46 | offset += sizeof(this->service); 47 | return offset; 48 | } 49 | 50 | virtual int deserialize(unsigned char *inbuffer) override 51 | { 52 | int offset = 0; 53 | union { 54 | int8_t real; 55 | uint8_t base; 56 | } u_status; 57 | u_status.base = 0; 58 | u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 59 | this->status = u_status.real; 60 | offset += sizeof(this->status); 61 | this->service = ((uint16_t) (*(inbuffer + offset))); 62 | this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 63 | offset += sizeof(this->service); 64 | return offset; 65 | } 66 | 67 | virtual const char * getType() override { return "sensor_msgs/NavSatStatus"; }; 68 | virtual const char * getMD5() override { return "331cdbddfa4bc96ffc3b9ad98900a54c"; }; 69 | 70 | }; 71 | 72 | } 73 | #endif 74 | -------------------------------------------------------------------------------- /src/sensor_msgs/RelativeHumidity.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_RelativeHumidity_h 2 | #define _ROS_sensor_msgs_RelativeHumidity_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | class RelativeHumidity : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef float _relative_humidity_type; 19 | _relative_humidity_type relative_humidity; 20 | typedef float _variance_type; 21 | _variance_type variance; 22 | 23 | RelativeHumidity(): 24 | header(), 25 | relative_humidity(0), 26 | variance(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->relative_humidity); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | offset += this->header.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->relative_humidity)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 45 | return offset; 46 | } 47 | 48 | virtual const char * getType() override { return "sensor_msgs/RelativeHumidity"; }; 49 | virtual const char * getMD5() override { return "8730015b05955b7e992ce29a2678d90f"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/sensor_msgs/Temperature.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_Temperature_h 2 | #define _ROS_sensor_msgs_Temperature_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | class Temperature : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef float _temperature_type; 19 | _temperature_type temperature; 20 | typedef float _variance_type; 21 | _variance_type variance; 22 | 23 | Temperature(): 24 | header(), 25 | temperature(0), 26 | variance(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->temperature); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | offset += this->header.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->temperature)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 45 | return offset; 46 | } 47 | 48 | virtual const char * getType() override { return "sensor_msgs/Temperature"; }; 49 | virtual const char * getMD5() override { return "ff71b307acdbe7c871a5a6d7ed359100"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/shape_msgs/MeshTriangle.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_shape_msgs_MeshTriangle_h 2 | #define _ROS_shape_msgs_MeshTriangle_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace shape_msgs 10 | { 11 | 12 | class MeshTriangle : public ros::Msg 13 | { 14 | public: 15 | uint32_t vertex_indices[3]; 16 | 17 | MeshTriangle(): 18 | vertex_indices() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | for( uint32_t i = 0; i < 3; i++){ 26 | *(outbuffer + offset + 0) = (this->vertex_indices[i] >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->vertex_indices[i] >> (8 * 1)) & 0xFF; 28 | *(outbuffer + offset + 2) = (this->vertex_indices[i] >> (8 * 2)) & 0xFF; 29 | *(outbuffer + offset + 3) = (this->vertex_indices[i] >> (8 * 3)) & 0xFF; 30 | offset += sizeof(this->vertex_indices[i]); 31 | } 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | for( uint32_t i = 0; i < 3; i++){ 39 | this->vertex_indices[i] = ((uint32_t) (*(inbuffer + offset))); 40 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 41 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 42 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 43 | offset += sizeof(this->vertex_indices[i]); 44 | } 45 | return offset; 46 | } 47 | 48 | virtual const char * getType() override { return "shape_msgs/MeshTriangle"; }; 49 | virtual const char * getMD5() override { return "23688b2e6d2de3d32fe8af104a903253"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/shape_msgs/Plane.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_shape_msgs_Plane_h 2 | #define _ROS_shape_msgs_Plane_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace shape_msgs 10 | { 11 | 12 | class Plane : public ros::Msg 13 | { 14 | public: 15 | float coef[4]; 16 | 17 | Plane(): 18 | coef() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | for( uint32_t i = 0; i < 4; i++){ 26 | offset += serializeAvrFloat64(outbuffer + offset, this->coef[i]); 27 | } 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) override 32 | { 33 | int offset = 0; 34 | for( uint32_t i = 0; i < 4; i++){ 35 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->coef[i])); 36 | } 37 | return offset; 38 | } 39 | 40 | virtual const char * getType() override { return "shape_msgs/Plane"; }; 41 | virtual const char * getMD5() override { return "2c1b92ed8f31492f8e73f6a4a44ca796"; }; 42 | 43 | }; 44 | 45 | } 46 | #endif 47 | -------------------------------------------------------------------------------- /src/std_msgs/Bool.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Bool_h 2 | #define _ROS_std_msgs_Bool_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Bool : public ros::Msg 13 | { 14 | public: 15 | typedef bool _data_type; 16 | _data_type data; 17 | 18 | Bool(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | bool real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | union { 40 | bool real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "std_msgs/Bool"; }; 51 | virtual const char * getMD5() override { return "8b94c1b53db61fb6aed406028ad6332a"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/std_msgs/Byte.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Byte_h 2 | #define _ROS_std_msgs_Byte_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Byte : public ros::Msg 13 | { 14 | public: 15 | typedef int8_t _data_type; 16 | _data_type data; 17 | 18 | Byte(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int8_t real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | union { 40 | int8_t real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "std_msgs/Byte"; }; 51 | virtual const char * getMD5() override { return "ad736a2e8818154c487bb80fe42ce43b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/std_msgs/Char.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Char_h 2 | #define _ROS_std_msgs_Char_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Char : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _data_type; 16 | _data_type data; 17 | 18 | Char(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | offset += sizeof(this->data); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) override 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | virtual const char * getType() override { return "std_msgs/Char"; }; 40 | virtual const char * getMD5() override { return "1bf77f25acecdedba0e224b162199717"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif 46 | -------------------------------------------------------------------------------- /src/std_msgs/Duration.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Duration_h 2 | #define _ROS_std_msgs_Duration_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "ros/duration.h" 9 | 10 | namespace std_msgs 11 | { 12 | 13 | class Duration : public ros::Msg 14 | { 15 | public: 16 | typedef ros::Duration _data_type; 17 | _data_type data; 18 | 19 | Duration(): 20 | data() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; 28 | *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; 29 | *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; 30 | *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; 31 | offset += sizeof(this->data.sec); 32 | *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; 33 | *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; 34 | *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; 35 | *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; 36 | offset += sizeof(this->data.nsec); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) override 41 | { 42 | int offset = 0; 43 | this->data.sec = ((uint32_t) (*(inbuffer + offset))); 44 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 45 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 46 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 47 | offset += sizeof(this->data.sec); 48 | this->data.nsec = ((uint32_t) (*(inbuffer + offset))); 49 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 50 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 51 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 52 | offset += sizeof(this->data.nsec); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "std_msgs/Duration"; }; 57 | virtual const char * getMD5() override { return "3e286caf4241d664e55f3ad380e2ae46"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/std_msgs/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Empty_h 2 | #define _ROS_std_msgs_Empty_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Empty : public ros::Msg 13 | { 14 | public: 15 | 16 | Empty() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "std_msgs/Empty"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/std_msgs/Float32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Float32_h 2 | #define _ROS_std_msgs_Float32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Float32 : public ros::Msg 13 | { 14 | public: 15 | typedef float _data_type; 16 | _data_type data; 17 | 18 | Float32(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | float real; 28 | uint32_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | float real; 44 | uint32_t base; 45 | } u_data; 46 | u_data.base = 0; 47 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->data = u_data.real; 52 | offset += sizeof(this->data); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "std_msgs/Float32"; }; 57 | virtual const char * getMD5() override { return "73fcbf46b49191e672908e50842a83d4"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/std_msgs/Float64.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Float64_h 2 | #define _ROS_std_msgs_Float64_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Float64 : public ros::Msg 13 | { 14 | public: 15 | typedef float _data_type; 16 | _data_type data; 17 | 18 | Float64(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | offset += serializeAvrFloat64(outbuffer + offset, this->data); 27 | return offset; 28 | } 29 | 30 | virtual int deserialize(unsigned char *inbuffer) override 31 | { 32 | int offset = 0; 33 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->data)); 34 | return offset; 35 | } 36 | 37 | virtual const char * getType() override { return "std_msgs/Float64"; }; 38 | virtual const char * getMD5() override { return "fdb28210bfa9d7c91146260178d9a584"; }; 39 | 40 | }; 41 | 42 | } 43 | #endif 44 | -------------------------------------------------------------------------------- /src/std_msgs/Int16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int16_h 2 | #define _ROS_std_msgs_Int16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Int16 : public ros::Msg 13 | { 14 | public: 15 | typedef int16_t _data_type; 16 | _data_type data; 17 | 18 | Int16(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int16_t real; 28 | uint16_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 33 | offset += sizeof(this->data); 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) override 38 | { 39 | int offset = 0; 40 | union { 41 | int16_t real; 42 | uint16_t base; 43 | } u_data; 44 | u_data.base = 0; 45 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); 46 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 47 | this->data = u_data.real; 48 | offset += sizeof(this->data); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType() override { return "std_msgs/Int16"; }; 53 | virtual const char * getMD5() override { return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/std_msgs/Int32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int32_h 2 | #define _ROS_std_msgs_Int32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Int32 : public ros::Msg 13 | { 14 | public: 15 | typedef int32_t _data_type; 16 | _data_type data; 17 | 18 | Int32(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int32_t real; 28 | uint32_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | int32_t real; 44 | uint32_t base; 45 | } u_data; 46 | u_data.base = 0; 47 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->data = u_data.real; 52 | offset += sizeof(this->data); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() override { return "std_msgs/Int32"; }; 57 | virtual const char * getMD5() override { return "da5909fbe378aeaf85e547e830cc1bb7"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/std_msgs/Int8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int8_h 2 | #define _ROS_std_msgs_Int8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Int8 : public ros::Msg 13 | { 14 | public: 15 | typedef int8_t _data_type; 16 | _data_type data; 17 | 18 | Int8(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | union { 27 | int8_t real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | union { 40 | int8_t real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "std_msgs/Int8"; }; 51 | virtual const char * getMD5() override { return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/std_msgs/String.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_String_h 2 | #define _ROS_std_msgs_String_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class String : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _data_type; 16 | _data_type data; 17 | 18 | String(): 19 | data("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_data = strlen(this->data); 27 | varToArr(outbuffer + offset, length_data); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->data, length_data); 30 | offset += length_data; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_data; 38 | arrToVar(length_data, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_data; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_data-1]=0; 44 | this->data = (char *)(inbuffer + offset-1); 45 | offset += length_data; 46 | return offset; 47 | } 48 | 49 | virtual const char * getType() { return "std_msgs/String"; }; 50 | virtual const char * getMD5() { return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif 56 | -------------------------------------------------------------------------------- /src/std_msgs/Time.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Time_h 2 | #define _ROS_std_msgs_Time_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "ros/time.h" 9 | 10 | namespace std_msgs 11 | { 12 | 13 | class Time : public ros::Msg 14 | { 15 | public: 16 | typedef ros::Time _data_type; 17 | _data_type data; 18 | 19 | Time(): 20 | data() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; 28 | *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; 29 | *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; 30 | *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; 31 | offset += sizeof(this->data.sec); 32 | *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; 33 | *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; 34 | *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; 35 | *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; 36 | offset += sizeof(this->data.nsec); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) 41 | { 42 | int offset = 0; 43 | this->data.sec = ((uint32_t) (*(inbuffer + offset))); 44 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 45 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 46 | this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 47 | offset += sizeof(this->data.sec); 48 | this->data.nsec = ((uint32_t) (*(inbuffer + offset))); 49 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 50 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 51 | this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 52 | offset += sizeof(this->data.nsec); 53 | return offset; 54 | } 55 | 56 | virtual const char * getType() { return "std_msgs/Time"; }; 57 | virtual const char * getMD5() { return "cd7166c74c552c311fbcc2fe5a7bc289"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif 63 | -------------------------------------------------------------------------------- /src/std_msgs/UInt16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt16_h 2 | #define _ROS_std_msgs_UInt16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt16 : public ros::Msg 13 | { 14 | public: 15 | typedef uint16_t _data_type; 16 | _data_type data; 17 | 18 | UInt16(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 28 | offset += sizeof(this->data); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) override 33 | { 34 | int offset = 0; 35 | this->data = ((uint16_t) (*(inbuffer + offset))); 36 | this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | virtual const char * getType() override { return "std_msgs/UInt16"; }; 42 | virtual const char * getMD5() override { return "1df79edf208b629fe6b81923a544552d"; }; 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/std_msgs/UInt32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt32_h 2 | #define _ROS_std_msgs_UInt32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt32 : public ros::Msg 13 | { 14 | public: 15 | typedef uint32_t _data_type; 16 | _data_type data; 17 | 18 | UInt32(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 28 | *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; 29 | *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; 30 | offset += sizeof(this->data); 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) override 35 | { 36 | int offset = 0; 37 | this->data = ((uint32_t) (*(inbuffer + offset))); 38 | this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 39 | this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 40 | this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 41 | offset += sizeof(this->data); 42 | return offset; 43 | } 44 | 45 | virtual const char * getType() override { return "std_msgs/UInt32"; }; 46 | virtual const char * getMD5() override { return "304a39449588c7f8ce2df6e8001c5fce"; }; 47 | 48 | }; 49 | 50 | } 51 | #endif 52 | -------------------------------------------------------------------------------- /src/std_msgs/UInt64.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt64_h 2 | #define _ROS_std_msgs_UInt64_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt64 : public ros::Msg 13 | { 14 | public: 15 | typedef uint64_t _data_type; 16 | _data_type data; 17 | 18 | UInt64(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 28 | *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; 29 | *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; 30 | *(outbuffer + offset + 4) = (this->data >> (8 * 4)) & 0xFF; 31 | *(outbuffer + offset + 5) = (this->data >> (8 * 5)) & 0xFF; 32 | *(outbuffer + offset + 6) = (this->data >> (8 * 6)) & 0xFF; 33 | *(outbuffer + offset + 7) = (this->data >> (8 * 7)) & 0xFF; 34 | offset += sizeof(this->data); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | this->data = ((uint64_t) (*(inbuffer + offset))); 42 | this->data |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 43 | this->data |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 44 | this->data |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 45 | this->data |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 46 | this->data |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 47 | this->data |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 48 | this->data |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 49 | offset += sizeof(this->data); 50 | return offset; 51 | } 52 | 53 | virtual const char * getType() override { return "std_msgs/UInt64"; }; 54 | virtual const char * getMD5() override { return "1b2a79973e8bf53d7b53acb71299cb57"; }; 55 | 56 | }; 57 | 58 | } 59 | #endif 60 | -------------------------------------------------------------------------------- /src/std_msgs/UInt8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt8_h 2 | #define _ROS_std_msgs_UInt8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt8 : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _data_type; 16 | _data_type data; 17 | 18 | UInt8(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const override 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | offset += sizeof(this->data); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) override 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | virtual const char * getType() override { return "std_msgs/UInt8"; }; 40 | virtual const char * getMD5() override { return "7c8164229e7d2c17eb95e9231617fdee"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif 46 | -------------------------------------------------------------------------------- /src/std_srvs/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_Empty_h 2 | #define _ROS_SERVICE_Empty_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace std_srvs 9 | { 10 | 11 | static const char EMPTY[] = "std_srvs/Empty"; 12 | 13 | class EmptyRequest : public ros::Msg 14 | { 15 | public: 16 | 17 | EmptyRequest() 18 | { 19 | } 20 | 21 | virtual int serialize(unsigned char *outbuffer) const override 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) override 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | virtual const char * getType() override { return EMPTY; }; 34 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 35 | 36 | }; 37 | 38 | class EmptyResponse : public ros::Msg 39 | { 40 | public: 41 | 42 | EmptyResponse() 43 | { 44 | } 45 | 46 | virtual int serialize(unsigned char *outbuffer) const override 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) override 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | virtual const char * getType() override { return EMPTY; }; 59 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /src/tests/array_test/array_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::geometry_msgs::PoseArray Test 3 | * Sums an array, publishes sum 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | 11 | ros::NodeHandle nh; 12 | 13 | 14 | bool set_; 15 | 16 | 17 | geometry_msgs::Pose sum_msg; 18 | ros::Publisher p("sum", &sum_msg); 19 | 20 | void messageCb(const geometry_msgs::PoseArray& msg){ 21 | sum_msg.position.x = 0; 22 | sum_msg.position.y = 0; 23 | sum_msg.position.z = 0; 24 | for(int i = 0; i < msg.poses_length; i++) 25 | { 26 | sum_msg.position.x += msg.poses[i].position.x; 27 | sum_msg.position.y += msg.poses[i].position.y; 28 | sum_msg.position.z += msg.poses[i].position.z; 29 | } 30 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 31 | } 32 | 33 | ros::Subscriber s("poses",messageCb); 34 | 35 | void setup() 36 | { 37 | pinMode(13, OUTPUT); 38 | nh.initNode(); 39 | nh.subscribe(s); 40 | nh.advertise(p); 41 | } 42 | 43 | void loop() 44 | { 45 | p.publish(&sum_msg); 46 | nh.spinOnce(); 47 | delay(10); 48 | } 49 | 50 | -------------------------------------------------------------------------------- /src/tests/float64_test/float64_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::std_msgs::Float64 Test 3 | * Receives a Float64 input, subtracts 1.0, and publishes it 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | 10 | ros::NodeHandle nh; 11 | 12 | float x; 13 | 14 | void messageCb( const std_msgs::Float64& msg){ 15 | x = msg.data - 1.0; 16 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 17 | } 18 | 19 | std_msgs::Float64 test; 20 | ros::Subscriber s("your_topic", &messageCb); 21 | ros::Publisher p("my_topic", &test); 22 | 23 | void setup() 24 | { 25 | pinMode(13, OUTPUT); 26 | nh.initNode(); 27 | nh.advertise(p); 28 | nh.subscribe(s); 29 | } 30 | 31 | void loop() 32 | { 33 | test.data = x; 34 | p.publish( &test ); 35 | nh.spinOnce(); 36 | delay(10); 37 | } 38 | 39 | -------------------------------------------------------------------------------- /src/tests/time_test/time_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::std_msgs::Time Test 3 | * Publishes current time 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | 11 | ros::NodeHandle nh; 12 | 13 | std_msgs::Time test; 14 | ros::Publisher p("my_topic", &test); 15 | 16 | void setup() 17 | { 18 | pinMode(13, OUTPUT); 19 | nh.initNode(); 20 | nh.advertise(p); 21 | } 22 | 23 | void loop() 24 | { 25 | test.data = nh.now(); 26 | p.publish( &test ); 27 | nh.spinOnce(); 28 | delay(10); 29 | } 30 | 31 | -------------------------------------------------------------------------------- /src/tf/tf.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2011, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote prducts derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #ifndef ROS_TF_H_ 36 | #define ROS_TF_H_ 37 | 38 | #include "geometry_msgs/TransformStamped.h" 39 | 40 | namespace tf 41 | { 42 | 43 | static inline geometry_msgs::Quaternion createQuaternionFromYaw(double yaw) 44 | { 45 | geometry_msgs::Quaternion q; 46 | q.x = 0; 47 | q.y = 0; 48 | q.z = sin(yaw * 0.5); 49 | q.w = cos(yaw * 0.5); 50 | return q; 51 | } 52 | 53 | } 54 | 55 | #endif 56 | 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformAction_h 2 | #define _ROS_tf2_msgs_LookupTransformAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "tf2_msgs/LookupTransformActionGoal.h" 9 | #include "tf2_msgs/LookupTransformActionResult.h" 10 | #include "tf2_msgs/LookupTransformActionFeedback.h" 11 | 12 | namespace tf2_msgs 13 | { 14 | 15 | class LookupTransformAction : public ros::Msg 16 | { 17 | public: 18 | typedef tf2_msgs::LookupTransformActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef tf2_msgs::LookupTransformActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef tf2_msgs::LookupTransformActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | LookupTransformAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->action_goal.serialize(outbuffer + offset); 36 | offset += this->action_result.serialize(outbuffer + offset); 37 | offset += this->action_feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->action_goal.deserialize(inbuffer + offset); 45 | offset += this->action_result.deserialize(inbuffer + offset); 46 | offset += this->action_feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "tf2_msgs/LookupTransformAction"; }; 51 | virtual const char * getMD5() override { return "7ee01ba91a56c2245c610992dbaa3c37"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformActionFeedback_h 2 | #define _ROS_tf2_msgs_LookupTransformActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "tf2_msgs/LookupTransformFeedback.h" 11 | 12 | namespace tf2_msgs 13 | { 14 | 15 | class LookupTransformActionFeedback : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef tf2_msgs::LookupTransformFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | LookupTransformActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->feedback.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->feedback.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "tf2_msgs/LookupTransformActionFeedback"; }; 51 | virtual const char * getMD5() override { return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformActionGoal_h 2 | #define _ROS_tf2_msgs_LookupTransformActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "tf2_msgs/LookupTransformGoal.h" 11 | 12 | namespace tf2_msgs 13 | { 14 | 15 | class LookupTransformActionGoal : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalID _goal_id_type; 21 | _goal_id_type goal_id; 22 | typedef tf2_msgs::LookupTransformGoal _goal_type; 23 | _goal_type goal; 24 | 25 | LookupTransformActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->goal_id.serialize(outbuffer + offset); 37 | offset += this->goal.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->goal_id.deserialize(inbuffer + offset); 46 | offset += this->goal.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "tf2_msgs/LookupTransformActionGoal"; }; 51 | virtual const char * getMD5() override { return "f2e7bcdb75c847978d0351a13e699da5"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformActionResult_h 2 | #define _ROS_tf2_msgs_LookupTransformActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "tf2_msgs/LookupTransformResult.h" 11 | 12 | namespace tf2_msgs 13 | { 14 | 15 | class LookupTransformActionResult : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef actionlib_msgs::GoalStatus _status_type; 21 | _status_type status; 22 | typedef tf2_msgs::LookupTransformResult _result_type; 23 | _result_type result; 24 | 25 | LookupTransformActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += this->status.serialize(outbuffer + offset); 37 | offset += this->result.serialize(outbuffer + offset); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += this->status.deserialize(inbuffer + offset); 46 | offset += this->result.deserialize(inbuffer + offset); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return "tf2_msgs/LookupTransformActionResult"; }; 51 | virtual const char * getMD5() override { return "ac26ce75a41384fa8bb4dc10f491ab90"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformFeedback_h 2 | #define _ROS_tf2_msgs_LookupTransformFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace tf2_msgs 10 | { 11 | 12 | class LookupTransformFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | LookupTransformFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const override 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) override 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual const char * getType() override { return "tf2_msgs/LookupTransformFeedback"; }; 33 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif 39 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformResult_h 2 | #define _ROS_tf2_msgs_LookupTransformResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/TransformStamped.h" 9 | #include "tf2_msgs/TF2Error.h" 10 | 11 | namespace tf2_msgs 12 | { 13 | 14 | class LookupTransformResult : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::TransformStamped _transform_type; 18 | _transform_type transform; 19 | typedef tf2_msgs::TF2Error _error_type; 20 | _error_type error; 21 | 22 | LookupTransformResult(): 23 | transform(), 24 | error() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->transform.serialize(outbuffer + offset); 32 | offset += this->error.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | offset += this->transform.deserialize(inbuffer + offset); 40 | offset += this->error.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | virtual const char * getType() override { return "tf2_msgs/LookupTransformResult"; }; 45 | virtual const char * getMD5() override { return "3fe5db6a19ca9cfb675418c5ad875c36"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /src/tf2_msgs/TF2Error.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_TF2Error_h 2 | #define _ROS_tf2_msgs_TF2Error_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace tf2_msgs 10 | { 11 | 12 | class TF2Error : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _error_type; 16 | _error_type error; 17 | typedef const char* _error_string_type; 18 | _error_string_type error_string; 19 | enum { NO_ERROR = 0 }; 20 | enum { LOOKUP_ERROR = 1 }; 21 | enum { CONNECTIVITY_ERROR = 2 }; 22 | enum { EXTRAPOLATION_ERROR = 3 }; 23 | enum { INVALID_ARGUMENT_ERROR = 4 }; 24 | enum { TIMEOUT_ERROR = 5 }; 25 | enum { TRANSFORM_ERROR = 6 }; 26 | 27 | TF2Error(): 28 | error(0), 29 | error_string("") 30 | { 31 | } 32 | 33 | virtual int serialize(unsigned char *outbuffer) const override 34 | { 35 | int offset = 0; 36 | *(outbuffer + offset + 0) = (this->error >> (8 * 0)) & 0xFF; 37 | offset += sizeof(this->error); 38 | uint32_t length_error_string = strlen(this->error_string); 39 | varToArr(outbuffer + offset, length_error_string); 40 | offset += 4; 41 | memcpy(outbuffer + offset, this->error_string, length_error_string); 42 | offset += length_error_string; 43 | return offset; 44 | } 45 | 46 | virtual int deserialize(unsigned char *inbuffer) override 47 | { 48 | int offset = 0; 49 | this->error = ((uint8_t) (*(inbuffer + offset))); 50 | offset += sizeof(this->error); 51 | uint32_t length_error_string; 52 | arrToVar(length_error_string, (inbuffer + offset)); 53 | offset += 4; 54 | for(unsigned int k= offset; k< offset+length_error_string; ++k){ 55 | inbuffer[k-1]=inbuffer[k]; 56 | } 57 | inbuffer[offset+length_error_string-1]=0; 58 | this->error_string = (char *)(inbuffer + offset-1); 59 | offset += length_error_string; 60 | return offset; 61 | } 62 | 63 | virtual const char * getType() override { return "tf2_msgs/TF2Error"; }; 64 | virtual const char * getMD5() override { return "bc6848fd6fd750c92e38575618a4917d"; }; 65 | 66 | }; 67 | 68 | } 69 | #endif 70 | -------------------------------------------------------------------------------- /src/topic_tools/DemuxAdd.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_DemuxAdd_h 2 | #define _ROS_SERVICE_DemuxAdd_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace topic_tools 9 | { 10 | 11 | static const char DEMUXADD[] = "topic_tools/DemuxAdd"; 12 | 13 | class DemuxAddRequest : public ros::Msg 14 | { 15 | public: 16 | typedef const char* _topic_type; 17 | _topic_type topic; 18 | 19 | DemuxAddRequest(): 20 | topic("") 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | uint32_t length_topic = strlen(this->topic); 28 | varToArr(outbuffer + offset, length_topic); 29 | offset += 4; 30 | memcpy(outbuffer + offset, this->topic, length_topic); 31 | offset += length_topic; 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | uint32_t length_topic; 39 | arrToVar(length_topic, (inbuffer + offset)); 40 | offset += 4; 41 | for(unsigned int k= offset; k< offset+length_topic; ++k){ 42 | inbuffer[k-1]=inbuffer[k]; 43 | } 44 | inbuffer[offset+length_topic-1]=0; 45 | this->topic = (char *)(inbuffer + offset-1); 46 | offset += length_topic; 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return DEMUXADD; }; 51 | virtual const char * getMD5() override { return "d8f94bae31b356b24d0427f80426d0c3"; }; 52 | 53 | }; 54 | 55 | class DemuxAddResponse : public ros::Msg 56 | { 57 | public: 58 | 59 | DemuxAddResponse() 60 | { 61 | } 62 | 63 | virtual int serialize(unsigned char *outbuffer) const override 64 | { 65 | int offset = 0; 66 | return offset; 67 | } 68 | 69 | virtual int deserialize(unsigned char *inbuffer) override 70 | { 71 | int offset = 0; 72 | return offset; 73 | } 74 | 75 | virtual const char * getType() override { return DEMUXADD; }; 76 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 77 | 78 | }; 79 | 80 | class DemuxAdd { 81 | public: 82 | typedef DemuxAddRequest Request; 83 | typedef DemuxAddResponse Response; 84 | }; 85 | 86 | } 87 | #endif 88 | -------------------------------------------------------------------------------- /src/topic_tools/MuxAdd.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_MuxAdd_h 2 | #define _ROS_SERVICE_MuxAdd_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace topic_tools 9 | { 10 | 11 | static const char MUXADD[] = "topic_tools/MuxAdd"; 12 | 13 | class MuxAddRequest : public ros::Msg 14 | { 15 | public: 16 | typedef const char* _topic_type; 17 | _topic_type topic; 18 | 19 | MuxAddRequest(): 20 | topic("") 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | uint32_t length_topic = strlen(this->topic); 28 | varToArr(outbuffer + offset, length_topic); 29 | offset += 4; 30 | memcpy(outbuffer + offset, this->topic, length_topic); 31 | offset += length_topic; 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | uint32_t length_topic; 39 | arrToVar(length_topic, (inbuffer + offset)); 40 | offset += 4; 41 | for(unsigned int k= offset; k< offset+length_topic; ++k){ 42 | inbuffer[k-1]=inbuffer[k]; 43 | } 44 | inbuffer[offset+length_topic-1]=0; 45 | this->topic = (char *)(inbuffer + offset-1); 46 | offset += length_topic; 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return MUXADD; }; 51 | virtual const char * getMD5() override { return "d8f94bae31b356b24d0427f80426d0c3"; }; 52 | 53 | }; 54 | 55 | class MuxAddResponse : public ros::Msg 56 | { 57 | public: 58 | 59 | MuxAddResponse() 60 | { 61 | } 62 | 63 | virtual int serialize(unsigned char *outbuffer) const override 64 | { 65 | int offset = 0; 66 | return offset; 67 | } 68 | 69 | virtual int deserialize(unsigned char *inbuffer) override 70 | { 71 | int offset = 0; 72 | return offset; 73 | } 74 | 75 | virtual const char * getType() override { return MUXADD; }; 76 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 77 | 78 | }; 79 | 80 | class MuxAdd { 81 | public: 82 | typedef MuxAddRequest Request; 83 | typedef MuxAddResponse Response; 84 | }; 85 | 86 | } 87 | #endif 88 | -------------------------------------------------------------------------------- /src/topic_tools/MuxDelete.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_MuxDelete_h 2 | #define _ROS_SERVICE_MuxDelete_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace topic_tools 9 | { 10 | 11 | static const char MUXDELETE[] = "topic_tools/MuxDelete"; 12 | 13 | class MuxDeleteRequest : public ros::Msg 14 | { 15 | public: 16 | typedef const char* _topic_type; 17 | _topic_type topic; 18 | 19 | MuxDeleteRequest(): 20 | topic("") 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | uint32_t length_topic = strlen(this->topic); 28 | varToArr(outbuffer + offset, length_topic); 29 | offset += 4; 30 | memcpy(outbuffer + offset, this->topic, length_topic); 31 | offset += length_topic; 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) override 36 | { 37 | int offset = 0; 38 | uint32_t length_topic; 39 | arrToVar(length_topic, (inbuffer + offset)); 40 | offset += 4; 41 | for(unsigned int k= offset; k< offset+length_topic; ++k){ 42 | inbuffer[k-1]=inbuffer[k]; 43 | } 44 | inbuffer[offset+length_topic-1]=0; 45 | this->topic = (char *)(inbuffer + offset-1); 46 | offset += length_topic; 47 | return offset; 48 | } 49 | 50 | virtual const char * getType() override { return MUXDELETE; }; 51 | virtual const char * getMD5() override { return "d8f94bae31b356b24d0427f80426d0c3"; }; 52 | 53 | }; 54 | 55 | class MuxDeleteResponse : public ros::Msg 56 | { 57 | public: 58 | 59 | MuxDeleteResponse() 60 | { 61 | } 62 | 63 | virtual int serialize(unsigned char *outbuffer) const override 64 | { 65 | int offset = 0; 66 | return offset; 67 | } 68 | 69 | virtual int deserialize(unsigned char *inbuffer) override 70 | { 71 | int offset = 0; 72 | return offset; 73 | } 74 | 75 | virtual const char * getType() override { return MUXDELETE; }; 76 | virtual const char * getMD5() override { return "d41d8cd98f00b204e9800998ecf8427e"; }; 77 | 78 | }; 79 | 80 | class MuxDelete { 81 | public: 82 | typedef MuxDeleteRequest Request; 83 | typedef MuxDeleteResponse Response; 84 | }; 85 | 86 | } 87 | #endif 88 | -------------------------------------------------------------------------------- /src/visualization_msgs/InteractiveMarkerPose.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_visualization_msgs_InteractiveMarkerPose_h 2 | #define _ROS_visualization_msgs_InteractiveMarkerPose_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Pose.h" 10 | 11 | namespace visualization_msgs 12 | { 13 | 14 | class InteractiveMarkerPose : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Pose _pose_type; 20 | _pose_type pose; 21 | typedef const char* _name_type; 22 | _name_type name; 23 | 24 | InteractiveMarkerPose(): 25 | header(), 26 | pose(), 27 | name("") 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const override 32 | { 33 | int offset = 0; 34 | offset += this->header.serialize(outbuffer + offset); 35 | offset += this->pose.serialize(outbuffer + offset); 36 | uint32_t length_name = strlen(this->name); 37 | varToArr(outbuffer + offset, length_name); 38 | offset += 4; 39 | memcpy(outbuffer + offset, this->name, length_name); 40 | offset += length_name; 41 | return offset; 42 | } 43 | 44 | virtual int deserialize(unsigned char *inbuffer) override 45 | { 46 | int offset = 0; 47 | offset += this->header.deserialize(inbuffer + offset); 48 | offset += this->pose.deserialize(inbuffer + offset); 49 | uint32_t length_name; 50 | arrToVar(length_name, (inbuffer + offset)); 51 | offset += 4; 52 | for(unsigned int k= offset; k< offset+length_name; ++k){ 53 | inbuffer[k-1]=inbuffer[k]; 54 | } 55 | inbuffer[offset+length_name-1]=0; 56 | this->name = (char *)(inbuffer + offset-1); 57 | offset += length_name; 58 | return offset; 59 | } 60 | 61 | virtual const char * getType() override { return "visualization_msgs/InteractiveMarkerPose"; }; 62 | virtual const char * getMD5() override { return "a6e6833209a196a38d798dadb02c81f8"; }; 63 | 64 | }; 65 | 66 | } 67 | #endif 68 | --------------------------------------------------------------------------------