├── .cproject ├── .project ├── Drivers ├── CMSIS │ ├── Device │ │ └── ST │ │ │ └── STM32F1xx │ │ │ └── Include │ │ │ ├── stm32f103xb.h │ │ │ ├── stm32f1xx.h │ │ │ └── system_stm32f1xx.h │ └── Include │ │ ├── arm_common_tables.h │ │ ├── arm_const_structs.h │ │ ├── arm_math.h │ │ ├── cmsis_armcc.h │ │ ├── cmsis_armcc_V6.h │ │ ├── cmsis_gcc.h │ │ ├── core_cm0.h │ │ ├── core_cm0plus.h │ │ ├── core_cm3.h │ │ ├── core_cm4.h │ │ ├── core_cm7.h │ │ ├── core_cmFunc.h │ │ ├── core_cmInstr.h │ │ ├── core_cmSimd.h │ │ ├── core_sc000.h │ │ └── core_sc300.h └── STM32F1xx_HAL_Driver │ ├── Inc │ ├── Legacy │ │ └── stm32_hal_legacy.h │ ├── stm32f1xx_hal.h │ ├── stm32f1xx_hal_cortex.h │ ├── stm32f1xx_hal_def.h │ ├── stm32f1xx_hal_dma.h │ ├── stm32f1xx_hal_dma_ex.h │ ├── stm32f1xx_hal_flash.h │ ├── stm32f1xx_hal_flash_ex.h │ ├── stm32f1xx_hal_gpio.h │ ├── stm32f1xx_hal_gpio_ex.h │ ├── stm32f1xx_hal_pcd.h │ ├── stm32f1xx_hal_pcd_ex.h │ ├── stm32f1xx_hal_pwr.h │ ├── stm32f1xx_hal_rcc.h │ ├── stm32f1xx_hal_rcc_ex.h │ ├── stm32f1xx_hal_tim.h │ ├── stm32f1xx_hal_tim_ex.h │ └── stm32f1xx_ll_usb.h │ └── Src │ ├── stm32f1xx_hal.c │ ├── stm32f1xx_hal_cortex.c │ ├── stm32f1xx_hal_dma.c │ ├── stm32f1xx_hal_flash.c │ ├── stm32f1xx_hal_flash_ex.c │ ├── stm32f1xx_hal_gpio.c │ ├── stm32f1xx_hal_gpio_ex.c │ ├── stm32f1xx_hal_pcd.c │ ├── stm32f1xx_hal_pcd_ex.c │ ├── stm32f1xx_hal_pwr.c │ ├── stm32f1xx_hal_rcc.c │ ├── stm32f1xx_hal_rcc_ex.c │ ├── stm32f1xx_hal_tim.c │ ├── stm32f1xx_hal_tim_ex.c │ └── stm32f1xx_ll_usb.c ├── Inc ├── main.h ├── stm32f1xx_hal_conf.h ├── stm32f1xx_it.h ├── usb_device.h ├── usbd_cdc_if.h ├── usbd_conf.h └── usbd_desc.h ├── LICENSE ├── Middlewares └── ST │ └── STM32_USB_Device_Library │ ├── Class │ └── CDC │ │ ├── Inc │ │ └── usbd_cdc.h │ │ └── Src │ │ └── usbd_cdc.c │ └── Core │ ├── Inc │ ├── usbd_core.h │ ├── usbd_ctlreq.h │ ├── usbd_def.h │ └── usbd_ioreq.h │ └── Src │ ├── usbd_core.c │ ├── usbd_ctlreq.c │ └── usbd_ioreq.c ├── README.md ├── ROS_stm32f1_USB_VCP Debug.cfg ├── ROS_stm32f1_USB_VCP.ioc ├── ROS_stm32f1_USB_VCP.xml ├── STM32F103C8Tx_FLASH.ld ├── Src ├── main.c ├── stm32f1xx_hal_msp.c ├── stm32f1xx_hal_timebase_TIM.c ├── stm32f1xx_it.c ├── system_stm32f1xx.c ├── usb_device.c ├── usbd_cdc_if.c ├── usbd_conf.c └── usbd_desc.c ├── ros_lib ├── STM32Hardware.h ├── 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 ├── actionlib_tutorials │ ├── AveragingAction.h │ ├── AveragingActionFeedback.h │ ├── AveragingActionGoal.h │ ├── AveragingActionResult.h │ ├── AveragingFeedback.h │ ├── AveragingGoal.h │ ├── AveragingResult.h │ ├── FibonacciAction.h │ ├── FibonacciActionFeedback.h │ ├── FibonacciActionGoal.h │ ├── FibonacciActionResult.h │ ├── FibonacciFeedback.h │ ├── FibonacciGoal.h │ └── FibonacciResult.h ├── bond │ ├── Constants.h │ └── Status.h ├── control_msgs │ ├── FollowJointTrajectoryAction.h │ ├── FollowJointTrajectoryActionFeedback.h │ ├── FollowJointTrajectoryActionGoal.h │ ├── FollowJointTrajectoryActionResult.h │ ├── FollowJointTrajectoryFeedback.h │ ├── FollowJointTrajectoryGoal.h │ ├── FollowJointTrajectoryResult.h │ ├── GripperCommand.h │ ├── GripperCommandAction.h │ ├── GripperCommandActionFeedback.h │ ├── GripperCommandActionGoal.h │ ├── GripperCommandActionResult.h │ ├── GripperCommandFeedback.h │ ├── GripperCommandGoal.h │ ├── GripperCommandResult.h │ ├── JointControllerState.h │ ├── JointTolerance.h │ ├── JointTrajectoryAction.h │ ├── JointTrajectoryActionFeedback.h │ ├── JointTrajectoryActionGoal.h │ ├── JointTrajectoryActionResult.h │ ├── JointTrajectoryControllerState.h │ ├── JointTrajectoryFeedback.h │ ├── JointTrajectoryGoal.h │ ├── JointTrajectoryResult.h │ ├── PidState.h │ ├── PointHeadAction.h │ ├── PointHeadActionFeedback.h │ ├── PointHeadActionGoal.h │ ├── PointHeadActionResult.h │ ├── PointHeadFeedback.h │ ├── PointHeadGoal.h │ ├── PointHeadResult.h │ ├── QueryCalibrationState.h │ ├── QueryTrajectoryState.h │ ├── SingleJointPositionAction.h │ ├── SingleJointPositionActionFeedback.h │ ├── SingleJointPositionActionGoal.h │ ├── SingleJointPositionActionResult.h │ ├── SingleJointPositionFeedback.h │ ├── SingleJointPositionGoal.h │ └── SingleJointPositionResult.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 ├── gazebo_msgs │ ├── ApplyBodyWrench.h │ ├── ApplyJointEffort.h │ ├── BodyRequest.h │ ├── ContactState.h │ ├── ContactsState.h │ ├── DeleteLight.h │ ├── DeleteModel.h │ ├── GetJointProperties.h │ ├── GetLightProperties.h │ ├── GetLinkProperties.h │ ├── GetLinkState.h │ ├── GetModelProperties.h │ ├── GetModelState.h │ ├── GetPhysicsProperties.h │ ├── GetWorldProperties.h │ ├── JointRequest.h │ ├── LinkState.h │ ├── LinkStates.h │ ├── ModelState.h │ ├── ModelStates.h │ ├── ODEJointProperties.h │ ├── ODEPhysics.h │ ├── SetJointProperties.h │ ├── SetJointTrajectory.h │ ├── SetLightProperties.h │ ├── SetLinkProperties.h │ ├── SetLinkState.h │ ├── SetModelConfiguration.h │ ├── SetModelState.h │ ├── SetPhysicsProperties.h │ ├── SpawnModel.h │ └── WorldState.h ├── 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 ├── laser_assembler │ ├── AssembleScans.h │ └── AssembleScans2.h ├── map_msgs │ ├── GetMapROI.h │ ├── GetPointMap.h │ ├── GetPointMapROI.h │ ├── OccupancyGridUpdate.h │ ├── PointCloud2Update.h │ ├── ProjectedMap.h │ ├── ProjectedMapInfo.h │ ├── ProjectedMapsInfo.h │ ├── SaveMap.h │ └── SetMapProjections.h ├── nodelet │ ├── NodeletList.h │ ├── NodeletLoad.h │ └── NodeletUnload.h ├── pcl_msgs │ ├── ModelCoefficients.h │ ├── PointIndices.h │ ├── PolygonMesh.h │ └── Vertices.h ├── polled_camera │ └── GetPolledImage.h ├── ros.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 ├── roscpp_tutorials │ └── TwoInts.h ├── rosgraph_msgs │ ├── Clock.h │ ├── Log.h │ └── TopicStatistics.h ├── rospy_tutorials │ ├── AddTwoInts.h │ ├── BadTwoInts.h │ ├── Floats.h │ └── HeaderString.h ├── rosserial_arduino │ ├── Adc.h │ └── Test.h ├── rosserial_msgs │ ├── Log.h │ ├── RequestMessageInfo.h │ ├── RequestParam.h │ ├── RequestServiceInfo.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 ├── smach_msgs │ ├── SmachContainerInitialStatusCmd.h │ ├── SmachContainerStatus.h │ └── SmachContainerStructure.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 ├── theora_image_transport │ └── Packet.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 ├── turtle_actionlib │ ├── ShapeAction.h │ ├── ShapeActionFeedback.h │ ├── ShapeActionGoal.h │ ├── ShapeActionResult.h │ ├── ShapeFeedback.h │ ├── ShapeGoal.h │ ├── ShapeResult.h │ └── Velocity.h ├── turtlesim │ ├── Color.h │ ├── Kill.h │ ├── Pose.h │ ├── SetPen.h │ ├── Spawn.h │ ├── TeleportAbsolute.h │ └── TeleportRelative.h └── visualization_msgs │ ├── ImageMarker.h │ ├── InteractiveMarker.h │ ├── InteractiveMarkerControl.h │ ├── InteractiveMarkerFeedback.h │ ├── InteractiveMarkerInit.h │ ├── InteractiveMarkerPose.h │ ├── InteractiveMarkerUpdate.h │ ├── Marker.h │ ├── MarkerArray.h │ └── MenuEntry.h ├── startup └── startup_stm32f103xb.s └── usr ├── cpp_main.cpp ├── cpp_main.h ├── ledStatus.cpp ├── ledStatus.h ├── nbt.cpp ├── nbt.h ├── ringbuffer.cpp └── ringbuffer.h /.project: -------------------------------------------------------------------------------- 1 | 2 | 3 | ROS_stm32f1_USB_VCP 4 | 5 | 6 | 7 | 8 | 9 | org.eclipse.cdt.managedbuilder.core.genmakebuilder 10 | clean,full,incremental, 11 | 12 | 13 | 14 | 15 | org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder 16 | full,incremental, 17 | 18 | 19 | 20 | 21 | 22 | org.eclipse.cdt.core.cnature 23 | org.eclipse.cdt.managedbuilder.core.managedBuildNature 24 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature 25 | fr.ac6.mcu.ide.core.MCUProjectNature 26 | org.eclipse.cdt.core.ccnature 27 | 28 | 29 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Itamare4/ROS_stm32f1_rosserial_USB_VCP/5fac421fa991db1ffe6fa469b93c0fb9d4ae2b87/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Itamare4/ROS_stm32f1_rosserial_USB_VCP/5fac421fa991db1ffe6fa469b93c0fb9d4ae2b87/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2018, Itamar Eliakim 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 | * Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | * 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 | * 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 | -------------------------------------------------------------------------------- /ROS_stm32f1_USB_VCP Debug.cfg: -------------------------------------------------------------------------------- 1 | source [find interface/stlink.cfg] 2 | 3 | set WORKAREASIZE 0x5000 4 | 5 | transport select "hla_swd" 6 | 7 | set CHIPNAME STM32F103C8Tx 8 | 9 | # Enable debug when in low power modes 10 | set ENABLE_LOW_POWER 1 11 | 12 | # Stop Watchdog counters when halt 13 | set STOP_WATCHDOG 1 14 | 15 | # STlink Debug clock frequency 16 | set CLOCK_FREQ 4000 17 | 18 | # use software system reset 19 | reset_config none 20 | set CONNECT_UNDER_RESET 0 21 | 22 | source [find target/stm32f1x.cfg] 23 | -------------------------------------------------------------------------------- /ROS_stm32f1_USB_VCP.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ROS_stm32f1_USB_VCP 5 | STM32F103C8Tx 6 | SWD 7 | ST-LinkV2-1 8 | 9 | 10 | -------------------------------------------------------------------------------- /ros_lib/STM32Hardware.h: -------------------------------------------------------------------------------- 1 | #ifndef _STM32_HARDWARE_H_ 2 | #define _STM32_HARDWARE_H_ 3 | 4 | #include "main.h" 5 | #include "stm32f1xx_hal.h" 6 | #include "usbd_cdc_if.h" 7 | #include "ringbuffer.h" 8 | 9 | extern struct ringbuffer rb; 10 | 11 | class STM32Hardware 12 | { 13 | public: 14 | STM32Hardware() { 15 | } 16 | 17 | void init() { 18 | } 19 | 20 | // Read a byte of data from ROS connection. 21 | // If no data , returns -1 22 | int read() 23 | { 24 | uint32_t r; 25 | uint8_t ch = -1; 26 | 27 | r = ringbuffer_getchar(&rb, &ch); 28 | 29 | if (1 == r) 30 | return ch; 31 | else 32 | return -1; 33 | } 34 | 35 | 36 | // Send a byte of data to ROS connection 37 | void write(uint8_t* data, int length) 38 | { 39 | CDC_Transmit_FS(data, length); 40 | } 41 | 42 | // Returns milliseconds since start of program 43 | unsigned long time(void) 44 | { 45 | return HAL_GetTick(); 46 | } 47 | 48 | }; 49 | 50 | #endif 51 | 52 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestAction"; }; 51 | const char * getMD5(){ return "991e87a72802262dfbe5d1b3cf6efc9a"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestActionFeedback"; }; 51 | const char * getMD5(){ return "6d3d0bf7fb3dda24779c010a9f3eb7cb"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestActionGoal"; }; 51 | const char * getMD5(){ return "348369c5b403676156094e8c159720bf"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestActionResult"; }; 51 | const char * getMD5(){ return "3d669e3a63aa986c667ea7b0f46ce85e"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestFeedback"; }; 57 | const char * getMD5(){ return "49ceb5b32ea3af22073ede4a0328249e"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestGoal"; }; 57 | const char * getMD5(){ return "18df0149936b7aa95588e3862476ebde"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestRequestAction"; }; 51 | const char * getMD5(){ return "dc44b1f4045dbf0d1db54423b3b86b30"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestRequestActionFeedback"; }; 51 | const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestRequestActionGoal"; }; 51 | const char * getMD5(){ return "1889556d3fef88f821c7cb004e4251f3"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestRequestActionResult"; }; 51 | const char * getMD5(){ return "0476d1fdf437a3a6e7d6d0e9f5561298"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "actionlib/TestRequestFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TestResult"; }; 57 | const char * getMD5(){ return "034a8e20d6a306665e3a5b340fab3f09"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TwoIntsAction"; }; 51 | const char * getMD5(){ return "6d1aa538c4bd6183a2dfb7fcac41ee50"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TwoIntsActionFeedback"; }; 51 | const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TwoIntsActionGoal"; }; 51 | const char * getMD5(){ return "684a2db55d6ffb8046fb9d6764ce0860"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "actionlib/TwoIntsActionResult"; }; 51 | const char * getMD5(){ return "3ba7dea8b8cddcae4528ade4ef74b6e7"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "actionlib/TwoIntsFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/AveragingAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_AveragingAction_h 2 | #define _ROS_actionlib_tutorials_AveragingAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib_tutorials/AveragingActionGoal.h" 9 | #include "actionlib_tutorials/AveragingActionResult.h" 10 | #include "actionlib_tutorials/AveragingActionFeedback.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class AveragingAction : public ros::Msg 16 | { 17 | public: 18 | typedef actionlib_tutorials::AveragingActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef actionlib_tutorials::AveragingActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef actionlib_tutorials::AveragingActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | AveragingAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/AveragingAction"; }; 51 | const char * getMD5(){ return "628678f2b4fa6a5951746a4a2d39e716"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/AveragingActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_AveragingActionFeedback_h 2 | #define _ROS_actionlib_tutorials_AveragingActionFeedback_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_tutorials/AveragingFeedback.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class AveragingActionFeedback : 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_tutorials::AveragingFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | AveragingActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/AveragingActionFeedback"; }; 51 | const char * getMD5(){ return "78a4a09241b1791069223ae7ebd5b16b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/AveragingActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_AveragingActionGoal_h 2 | #define _ROS_actionlib_tutorials_AveragingActionGoal_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_tutorials/AveragingGoal.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class AveragingActionGoal : 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_tutorials::AveragingGoal _goal_type; 23 | _goal_type goal; 24 | 25 | AveragingActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/AveragingActionGoal"; }; 51 | const char * getMD5(){ return "1561825b734ebd6039851c501e3fb570"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/AveragingActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_AveragingActionResult_h 2 | #define _ROS_actionlib_tutorials_AveragingActionResult_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_tutorials/AveragingResult.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class AveragingActionResult : 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_tutorials::AveragingResult _result_type; 23 | _result_type result; 24 | 25 | AveragingActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/AveragingActionResult"; }; 51 | const char * getMD5(){ return "8672cb489d347580acdcd05c5d497497"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/FibonacciAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_FibonacciAction_h 2 | #define _ROS_actionlib_tutorials_FibonacciAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib_tutorials/FibonacciActionGoal.h" 9 | #include "actionlib_tutorials/FibonacciActionResult.h" 10 | #include "actionlib_tutorials/FibonacciActionFeedback.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class FibonacciAction : public ros::Msg 16 | { 17 | public: 18 | typedef actionlib_tutorials::FibonacciActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef actionlib_tutorials::FibonacciActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef actionlib_tutorials::FibonacciActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | FibonacciAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/FibonacciAction"; }; 51 | const char * getMD5(){ return "f59df5767bf7634684781c92598b2406"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/FibonacciActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_FibonacciActionFeedback_h 2 | #define _ROS_actionlib_tutorials_FibonacciActionFeedback_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_tutorials/FibonacciFeedback.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class FibonacciActionFeedback : 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_tutorials::FibonacciFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | FibonacciActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/FibonacciActionFeedback"; }; 51 | const char * getMD5(){ return "73b8497a9f629a31c0020900e4148f07"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/FibonacciActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_FibonacciActionGoal_h 2 | #define _ROS_actionlib_tutorials_FibonacciActionGoal_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_tutorials/FibonacciGoal.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class FibonacciActionGoal : 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_tutorials::FibonacciGoal _goal_type; 23 | _goal_type goal; 24 | 25 | FibonacciActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/FibonacciActionGoal"; }; 51 | const char * getMD5(){ return "006871c7fa1d0e3d5fe2226bf17b2a94"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/FibonacciActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_FibonacciActionResult_h 2 | #define _ROS_actionlib_tutorials_FibonacciActionResult_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_tutorials/FibonacciResult.h" 11 | 12 | namespace actionlib_tutorials 13 | { 14 | 15 | class FibonacciActionResult : 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_tutorials::FibonacciResult _result_type; 23 | _result_type result; 24 | 25 | FibonacciActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "actionlib_tutorials/FibonacciActionResult"; }; 51 | const char * getMD5(){ return "bee73a9fe29ae25e966e105f5553dd03"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/actionlib_tutorials/FibonacciGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_tutorials_FibonacciGoal_h 2 | #define _ROS_actionlib_tutorials_FibonacciGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib_tutorials 10 | { 11 | 12 | class FibonacciGoal : public ros::Msg 13 | { 14 | public: 15 | typedef int32_t _order_type; 16 | _order_type order; 17 | 18 | FibonacciGoal(): 19 | order(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | int32_t real; 28 | uint32_t base; 29 | } u_order; 30 | u_order.real = this->order; 31 | *(outbuffer + offset + 0) = (u_order.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_order.base >> (8 * 1)) & 0xFF; 33 | *(outbuffer + offset + 2) = (u_order.base >> (8 * 2)) & 0xFF; 34 | *(outbuffer + offset + 3) = (u_order.base >> (8 * 3)) & 0xFF; 35 | offset += sizeof(this->order); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) 40 | { 41 | int offset = 0; 42 | union { 43 | int32_t real; 44 | uint32_t base; 45 | } u_order; 46 | u_order.base = 0; 47 | u_order.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_order.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | u_order.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 50 | u_order.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 51 | this->order = u_order.real; 52 | offset += sizeof(this->order); 53 | return offset; 54 | } 55 | 56 | const char * getType(){ return "actionlib_tutorials/FibonacciGoal"; }; 57 | const char * getMD5(){ return "6889063349a00b249bd1661df429d822"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "bond/Constants"; }; 39 | const char * getMD5(){ return "6fc594dc1d7bd7919077042712f8c8b0"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/FollowJointTrajectoryActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_FollowJointTrajectoryActionFeedback_h 2 | #define _ROS_control_msgs_FollowJointTrajectoryActionFeedback_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 "control_msgs/FollowJointTrajectoryFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class FollowJointTrajectoryActionFeedback : 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 control_msgs::FollowJointTrajectoryFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | FollowJointTrajectoryActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/FollowJointTrajectoryActionFeedback"; }; 51 | const char * getMD5(){ return "d8920dc4eae9fc107e00999cce4be641"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/FollowJointTrajectoryActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_FollowJointTrajectoryActionGoal_h 2 | #define _ROS_control_msgs_FollowJointTrajectoryActionGoal_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 "control_msgs/FollowJointTrajectoryGoal.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class FollowJointTrajectoryActionGoal : 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 control_msgs::FollowJointTrajectoryGoal _goal_type; 23 | _goal_type goal; 24 | 25 | FollowJointTrajectoryActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/FollowJointTrajectoryActionGoal"; }; 51 | const char * getMD5(){ return "cff5c1d533bf2f82dd0138d57f4304bb"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/FollowJointTrajectoryActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_FollowJointTrajectoryActionResult_h 2 | #define _ROS_control_msgs_FollowJointTrajectoryActionResult_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 "control_msgs/FollowJointTrajectoryResult.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class FollowJointTrajectoryActionResult : 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 control_msgs::FollowJointTrajectoryResult _result_type; 23 | _result_type result; 24 | 25 | FollowJointTrajectoryActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/FollowJointTrajectoryActionResult"; }; 51 | const char * getMD5(){ return "c4fb3b000dc9da4fd99699380efcc5d9"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommand.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommand_h 2 | #define _ROS_control_msgs_GripperCommand_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class GripperCommand : public ros::Msg 13 | { 14 | public: 15 | typedef float _position_type; 16 | _position_type position; 17 | typedef float _max_effort_type; 18 | _max_effort_type max_effort; 19 | 20 | GripperCommand(): 21 | position(0), 22 | max_effort(0) 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | offset += serializeAvrFloat64(outbuffer + offset, this->position); 30 | offset += serializeAvrFloat64(outbuffer + offset, this->max_effort); 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); 38 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_effort)); 39 | return offset; 40 | } 41 | 42 | const char * getType(){ return "control_msgs/GripperCommand"; }; 43 | const char * getMD5(){ return "680acaff79486f017132a7f198d40f08"; }; 44 | 45 | }; 46 | 47 | } 48 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommandAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandAction_h 2 | #define _ROS_control_msgs_GripperCommandAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "control_msgs/GripperCommandActionGoal.h" 9 | #include "control_msgs/GripperCommandActionResult.h" 10 | #include "control_msgs/GripperCommandActionFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class GripperCommandAction : public ros::Msg 16 | { 17 | public: 18 | typedef control_msgs::GripperCommandActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef control_msgs::GripperCommandActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef control_msgs::GripperCommandActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | GripperCommandAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/GripperCommandAction"; }; 51 | const char * getMD5(){ return "950b2a6ebe831f5d4f4ceaba3d8be01e"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommandActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandActionFeedback_h 2 | #define _ROS_control_msgs_GripperCommandActionFeedback_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 "control_msgs/GripperCommandFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class GripperCommandActionFeedback : 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 control_msgs::GripperCommandFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | GripperCommandActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/GripperCommandActionFeedback"; }; 51 | const char * getMD5(){ return "653dff30c045f5e6ff3feb3409f4558d"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommandActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandActionGoal_h 2 | #define _ROS_control_msgs_GripperCommandActionGoal_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 "control_msgs/GripperCommandGoal.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class GripperCommandActionGoal : 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 control_msgs::GripperCommandGoal _goal_type; 23 | _goal_type goal; 24 | 25 | GripperCommandActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/GripperCommandActionGoal"; }; 51 | const char * getMD5(){ return "aa581f648a35ed681db2ec0bf7a82bea"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommandActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandActionResult_h 2 | #define _ROS_control_msgs_GripperCommandActionResult_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 "control_msgs/GripperCommandResult.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class GripperCommandActionResult : 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 control_msgs::GripperCommandResult _result_type; 23 | _result_type result; 24 | 25 | GripperCommandActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/GripperCommandActionResult"; }; 51 | const char * getMD5(){ return "143702cb2df0f163c5283cedc5efc6b6"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/GripperCommandGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandGoal_h 2 | #define _ROS_control_msgs_GripperCommandGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "control_msgs/GripperCommand.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class GripperCommandGoal : public ros::Msg 14 | { 15 | public: 16 | typedef control_msgs::GripperCommand _command_type; 17 | _command_type command; 18 | 19 | GripperCommandGoal(): 20 | command() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->command.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->command.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "control_msgs/GripperCommandGoal"; }; 39 | const char * getMD5(){ return "86fd82f4ddc48a4cb6856cfa69217e43"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryAction_h 2 | #define _ROS_control_msgs_JointTrajectoryAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "control_msgs/JointTrajectoryActionGoal.h" 9 | #include "control_msgs/JointTrajectoryActionResult.h" 10 | #include "control_msgs/JointTrajectoryActionFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class JointTrajectoryAction : public ros::Msg 16 | { 17 | public: 18 | typedef control_msgs::JointTrajectoryActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef control_msgs::JointTrajectoryActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef control_msgs::JointTrajectoryActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | JointTrajectoryAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/JointTrajectoryAction"; }; 51 | const char * getMD5(){ return "a04ba3ee8f6a2d0985a6aeaf23d9d7ad"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryActionFeedback_h 2 | #define _ROS_control_msgs_JointTrajectoryActionFeedback_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 "control_msgs/JointTrajectoryFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class JointTrajectoryActionFeedback : 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 control_msgs::JointTrajectoryFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | JointTrajectoryActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/JointTrajectoryActionFeedback"; }; 51 | const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryActionGoal_h 2 | #define _ROS_control_msgs_JointTrajectoryActionGoal_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 "control_msgs/JointTrajectoryGoal.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class JointTrajectoryActionGoal : 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 control_msgs::JointTrajectoryGoal _goal_type; 23 | _goal_type goal; 24 | 25 | JointTrajectoryActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/JointTrajectoryActionGoal"; }; 51 | const char * getMD5(){ return "a99e83ef6185f9fdd7693efe99623a86"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryActionResult_h 2 | #define _ROS_control_msgs_JointTrajectoryActionResult_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 "control_msgs/JointTrajectoryResult.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class JointTrajectoryActionResult : 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 control_msgs::JointTrajectoryResult _result_type; 23 | _result_type result; 24 | 25 | JointTrajectoryActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/JointTrajectoryActionResult"; }; 51 | const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryFeedback_h 2 | #define _ROS_control_msgs_JointTrajectoryFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class JointTrajectoryFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | JointTrajectoryFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/JointTrajectoryFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryGoal_h 2 | #define _ROS_control_msgs_JointTrajectoryGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "trajectory_msgs/JointTrajectory.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class JointTrajectoryGoal : public ros::Msg 14 | { 15 | public: 16 | typedef trajectory_msgs::JointTrajectory _trajectory_type; 17 | _trajectory_type trajectory; 18 | 19 | JointTrajectoryGoal(): 20 | trajectory() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->trajectory.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->trajectory.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "control_msgs/JointTrajectoryGoal"; }; 39 | const char * getMD5(){ return "2a0eff76c870e8595636c2a562ca298e"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/JointTrajectoryResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryResult_h 2 | #define _ROS_control_msgs_JointTrajectoryResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class JointTrajectoryResult : public ros::Msg 13 | { 14 | public: 15 | 16 | JointTrajectoryResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/JointTrajectoryResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadAction_h 2 | #define _ROS_control_msgs_PointHeadAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "control_msgs/PointHeadActionGoal.h" 9 | #include "control_msgs/PointHeadActionResult.h" 10 | #include "control_msgs/PointHeadActionFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class PointHeadAction : public ros::Msg 16 | { 17 | public: 18 | typedef control_msgs::PointHeadActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef control_msgs::PointHeadActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef control_msgs::PointHeadActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | PointHeadAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/PointHeadAction"; }; 51 | const char * getMD5(){ return "7252920f1243de1b741f14f214125371"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadActionFeedback_h 2 | #define _ROS_control_msgs_PointHeadActionFeedback_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 "control_msgs/PointHeadFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class PointHeadActionFeedback : 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 control_msgs::PointHeadFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | PointHeadActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/PointHeadActionFeedback"; }; 51 | const char * getMD5(){ return "33c9244957176bbba97dd641119e8460"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadActionGoal_h 2 | #define _ROS_control_msgs_PointHeadActionGoal_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 "control_msgs/PointHeadGoal.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class PointHeadActionGoal : 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 control_msgs::PointHeadGoal _goal_type; 23 | _goal_type goal; 24 | 25 | PointHeadActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/PointHeadActionGoal"; }; 51 | const char * getMD5(){ return "b53a8323d0ba7b310ba17a2d3a82a6b8"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadActionResult_h 2 | #define _ROS_control_msgs_PointHeadActionResult_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 "control_msgs/PointHeadResult.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class PointHeadActionResult : 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 control_msgs::PointHeadResult _result_type; 23 | _result_type result; 24 | 25 | PointHeadActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/PointHeadActionResult"; }; 51 | const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadFeedback_h 2 | #define _ROS_control_msgs_PointHeadFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class PointHeadFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef float _pointing_angle_error_type; 16 | _pointing_angle_error_type pointing_angle_error; 17 | 18 | PointHeadFeedback(): 19 | pointing_angle_error(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | offset += serializeAvrFloat64(outbuffer + offset, this->pointing_angle_error); 27 | return offset; 28 | } 29 | 30 | virtual int deserialize(unsigned char *inbuffer) 31 | { 32 | int offset = 0; 33 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->pointing_angle_error)); 34 | return offset; 35 | } 36 | 37 | const char * getType(){ return "control_msgs/PointHeadFeedback"; }; 38 | const char * getMD5(){ return "cce80d27fd763682da8805a73316cab4"; }; 39 | 40 | }; 41 | 42 | } 43 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/PointHeadResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadResult_h 2 | #define _ROS_control_msgs_PointHeadResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class PointHeadResult : public ros::Msg 13 | { 14 | public: 15 | 16 | PointHeadResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/PointHeadResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/SingleJointPositionActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionActionFeedback_h 2 | #define _ROS_control_msgs_SingleJointPositionActionFeedback_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 "control_msgs/SingleJointPositionFeedback.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class SingleJointPositionActionFeedback : 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 control_msgs::SingleJointPositionFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | SingleJointPositionActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/SingleJointPositionActionFeedback"; }; 51 | const char * getMD5(){ return "3503b7cf8972f90d245850a5d8796cfa"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/SingleJointPositionActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionActionGoal_h 2 | #define _ROS_control_msgs_SingleJointPositionActionGoal_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 "control_msgs/SingleJointPositionGoal.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class SingleJointPositionActionGoal : 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 control_msgs::SingleJointPositionGoal _goal_type; 23 | _goal_type goal; 24 | 25 | SingleJointPositionActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/SingleJointPositionActionGoal"; }; 51 | const char * getMD5(){ return "4b0d3d091471663e17749c1d0db90f61"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/SingleJointPositionActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionActionResult_h 2 | #define _ROS_control_msgs_SingleJointPositionActionResult_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 "control_msgs/SingleJointPositionResult.h" 11 | 12 | namespace control_msgs 13 | { 14 | 15 | class SingleJointPositionActionResult : 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 control_msgs::SingleJointPositionResult _result_type; 23 | _result_type result; 24 | 25 | SingleJointPositionActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "control_msgs/SingleJointPositionActionResult"; }; 51 | const char * getMD5(){ return "1eb06eeff08fa7ea874431638cb52332"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/SingleJointPositionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionFeedback_h 2 | #define _ROS_control_msgs_SingleJointPositionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class SingleJointPositionFeedback : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef float _position_type; 19 | _position_type position; 20 | typedef float _velocity_type; 21 | _velocity_type velocity; 22 | typedef float _error_type; 23 | _error_type error; 24 | 25 | SingleJointPositionFeedback(): 26 | header(), 27 | position(0), 28 | velocity(0), 29 | error(0) 30 | { 31 | } 32 | 33 | virtual int serialize(unsigned char *outbuffer) const 34 | { 35 | int offset = 0; 36 | offset += this->header.serialize(outbuffer + offset); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->position); 38 | offset += serializeAvrFloat64(outbuffer + offset, this->velocity); 39 | offset += serializeAvrFloat64(outbuffer + offset, this->error); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); 48 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->velocity)); 49 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->error)); 50 | return offset; 51 | } 52 | 53 | const char * getType(){ return "control_msgs/SingleJointPositionFeedback"; }; 54 | const char * getMD5(){ return "8cee65610a3d08e0a1bded82f146f1fd"; }; 55 | 56 | }; 57 | 58 | } 59 | #endif -------------------------------------------------------------------------------- /ros_lib/control_msgs/SingleJointPositionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionResult_h 2 | #define _ROS_control_msgs_SingleJointPositionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class SingleJointPositionResult : public ros::Msg 13 | { 14 | public: 15 | 16 | SingleJointPositionResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/SingleJointPositionResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "dynamic_reconfigure/DoubleParameter"; }; 55 | const char * getMD5(){ return "d8512f27253c0f65f928a67c329cd658"; }; 56 | 57 | }; 58 | 59 | } 60 | #endif -------------------------------------------------------------------------------- /ros_lib/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 24 | { 25 | int offset = 0; 26 | return offset; 27 | } 28 | 29 | virtual int deserialize(unsigned char *inbuffer) 30 | { 31 | int offset = 0; 32 | return offset; 33 | } 34 | 35 | const char * getType(){ return "dynamic_reconfigure/SensorLevels"; }; 36 | const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; }; 37 | 38 | }; 39 | 40 | } 41 | #endif -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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(13, HIGH-digitalRead(13)); // blink the led 13 | } 14 | 15 | ros::Subscriber sub("toggle_led", &messageCb ); 16 | 17 | void setup() 18 | { 19 | pinMode(13, OUTPUT); 20 | nh.initNode(); 21 | nh.subscribe(sub); 22 | } 23 | 24 | void loop() 25 | { 26 | nh.spinOnce(); 27 | delay(1); 28 | } 29 | 30 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Accel"; }; 44 | const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/AccelStamped"; }; 45 | const char * getMD5(){ return "d8a98a5d81351b6eb0578c78557e7659"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/AccelWithCovariance"; }; 47 | const char * getMD5(){ return "ad5a718d699c6be72a02b8d6a139f334"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/AccelWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "96adb295225031ec8d57fb4251b0a886"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/InertiaStamped"; }; 45 | const char * getMD5(){ return "ddee48caeab5a966c5e8d166654a9ac7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Point"; }; 48 | const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/PointStamped"; }; 45 | const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/PolygonStamped"; }; 45 | const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Pose"; }; 45 | const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Pose2D"; }; 48 | const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/PoseStamped"; }; 45 | const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/PoseWithCovariance"; }; 47 | const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Quaternion"; }; 53 | const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/QuaternionStamped"; }; 45 | const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Transform"; }; 45 | const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Twist"; }; 44 | const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/TwistStamped"; }; 45 | const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; 47 | const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Vector3"; }; 48 | const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Vector3Stamped"; }; 45 | const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/Wrench"; }; 44 | const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "geometry_msgs/WrenchStamped"; }; 45 | const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /ros_lib/map_msgs/GetPointMap.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_GetPointMap_h 2 | #define _ROS_SERVICE_GetPointMap_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | #include "sensor_msgs/PointCloud2.h" 8 | 9 | namespace map_msgs 10 | { 11 | 12 | static const char GETPOINTMAP[] = "map_msgs/GetPointMap"; 13 | 14 | class GetPointMapRequest : public ros::Msg 15 | { 16 | public: 17 | 18 | GetPointMapRequest() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | const char * getType(){ return GETPOINTMAP; }; 35 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 36 | 37 | }; 38 | 39 | class GetPointMapResponse : public ros::Msg 40 | { 41 | public: 42 | typedef sensor_msgs::PointCloud2 _map_type; 43 | _map_type map; 44 | 45 | GetPointMapResponse(): 46 | map() 47 | { 48 | } 49 | 50 | virtual int serialize(unsigned char *outbuffer) const 51 | { 52 | int offset = 0; 53 | offset += this->map.serialize(outbuffer + offset); 54 | return offset; 55 | } 56 | 57 | virtual int deserialize(unsigned char *inbuffer) 58 | { 59 | int offset = 0; 60 | offset += this->map.deserialize(inbuffer + offset); 61 | return offset; 62 | } 63 | 64 | const char * getType(){ return GETPOINTMAP; }; 65 | const char * getMD5(){ return "b84fbb39505086eb6a62d933c75cb7b4"; }; 66 | 67 | }; 68 | 69 | class GetPointMap { 70 | public: 71 | typedef GetPointMapRequest Request; 72 | typedef GetPointMapResponse Response; 73 | }; 74 | 75 | } 76 | #endif 77 | -------------------------------------------------------------------------------- /ros_lib/map_msgs/ProjectedMap.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_map_msgs_ProjectedMap_h 2 | #define _ROS_map_msgs_ProjectedMap_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/OccupancyGrid.h" 9 | 10 | namespace map_msgs 11 | { 12 | 13 | class ProjectedMap : public ros::Msg 14 | { 15 | public: 16 | typedef nav_msgs::OccupancyGrid _map_type; 17 | _map_type map; 18 | typedef float _min_z_type; 19 | _min_z_type min_z; 20 | typedef float _max_z_type; 21 | _max_z_type max_z; 22 | 23 | ProjectedMap(): 24 | map(), 25 | min_z(0), 26 | max_z(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const 31 | { 32 | int offset = 0; 33 | offset += this->map.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->min_z); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->max_z); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) 40 | { 41 | int offset = 0; 42 | offset += this->map.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_z)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_z)); 45 | return offset; 46 | } 47 | 48 | const char * getType(){ return "map_msgs/ProjectedMap"; }; 49 | const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/map_msgs/SaveMap.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_SaveMap_h 2 | #define _ROS_SERVICE_SaveMap_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | #include "std_msgs/String.h" 8 | 9 | namespace map_msgs 10 | { 11 | 12 | static const char SAVEMAP[] = "map_msgs/SaveMap"; 13 | 14 | class SaveMapRequest : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::String _filename_type; 18 | _filename_type filename; 19 | 20 | SaveMapRequest(): 21 | filename() 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const 26 | { 27 | int offset = 0; 28 | offset += this->filename.serialize(outbuffer + offset); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | offset += this->filename.deserialize(inbuffer + offset); 36 | return offset; 37 | } 38 | 39 | const char * getType(){ return SAVEMAP; }; 40 | const char * getMD5(){ return "716e25f9d9dc76ceba197f93cbf05dc7"; }; 41 | 42 | }; 43 | 44 | class SaveMapResponse : public ros::Msg 45 | { 46 | public: 47 | 48 | SaveMapResponse() 49 | { 50 | } 51 | 52 | virtual int serialize(unsigned char *outbuffer) const 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | virtual int deserialize(unsigned char *inbuffer) 59 | { 60 | int offset = 0; 61 | return offset; 62 | } 63 | 64 | const char * getType(){ return SAVEMAP; }; 65 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 66 | 67 | }; 68 | 69 | class SaveMap { 70 | public: 71 | typedef SaveMapRequest Request; 72 | typedef SaveMapResponse Response; 73 | }; 74 | 75 | } 76 | #endif 77 | -------------------------------------------------------------------------------- /ros_lib/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 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | const char * getType(){ return EMPTY; }; 34 | const char * getMD5(){ 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 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | const char * getType(){ return EMPTY; }; 59 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /ros_lib/rospy_tutorials/HeaderString.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rospy_tutorials_HeaderString_h 2 | #define _ROS_rospy_tutorials_HeaderString_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace rospy_tutorials 11 | { 12 | 13 | class HeaderString : public ros::Msg 14 | { 15 | public: 16 | typedef std_msgs::Header _header_type; 17 | _header_type header; 18 | typedef const char* _data_type; 19 | _data_type data; 20 | 21 | HeaderString(): 22 | header(), 23 | data("") 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const 28 | { 29 | int offset = 0; 30 | offset += this->header.serialize(outbuffer + offset); 31 | uint32_t length_data = strlen(this->data); 32 | varToArr(outbuffer + offset, length_data); 33 | offset += 4; 34 | memcpy(outbuffer + offset, this->data, length_data); 35 | offset += length_data; 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) 40 | { 41 | int offset = 0; 42 | offset += this->header.deserialize(inbuffer + offset); 43 | uint32_t length_data; 44 | arrToVar(length_data, (inbuffer + offset)); 45 | offset += 4; 46 | for(unsigned int k= offset; k< offset+length_data; ++k){ 47 | inbuffer[k-1]=inbuffer[k]; 48 | } 49 | inbuffer[offset+length_data-1]=0; 50 | this->data = (char *)(inbuffer + offset-1); 51 | offset += length_data; 52 | return offset; 53 | } 54 | 55 | const char * getType(){ return "rospy_tutorials/HeaderString"; }; 56 | const char * getMD5(){ return "c99a9440709e4d4a9716d55b8270d5e7"; }; 57 | 58 | }; 59 | 60 | } 61 | #endif -------------------------------------------------------------------------------- /ros_lib/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 | const char * getType(){ return "rosserial_msgs/Log"; }; 62 | const char * getMD5(){ return "11abd731c25933261cd6183bd12d6295"; }; 63 | 64 | }; 65 | 66 | } 67 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "sensor_msgs/FluidPressure"; }; 49 | const char * getMD5(){ return "804dc5cea1c5306d6a2eb80b9833befe"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "sensor_msgs/Illuminance"; }; 49 | const char * getMD5(){ return "8cf5febb0952fca9d650c3d11a81a188"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "sensor_msgs/MagneticField"; }; 53 | const char * getMD5(){ return "2f3b0b43eed0c9501de0fa3ff89a45aa"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "sensor_msgs/RelativeHumidity"; }; 49 | const char * getMD5(){ return "8730015b05955b7e992ce29a2678d90f"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "sensor_msgs/Temperature"; }; 49 | const char * getMD5(){ return "ff71b307acdbe7c871a5a6d7ed359100"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "shape_msgs/MeshTriangle"; }; 49 | const char * getMD5(){ return "23688b2e6d2de3d32fe8af104a903253"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "shape_msgs/Plane"; }; 41 | const char * getMD5(){ return "2c1b92ed8f31492f8e73f6a4a44ca796"; }; 42 | 43 | }; 44 | 45 | } 46 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Bool"; }; 51 | const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Byte"; }; 51 | const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | const char * getType(){ return "std_msgs/Char"; }; 40 | const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif -------------------------------------------------------------------------------- /ros_lib/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 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "std_msgs/Empty"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Float32"; }; 57 | const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 24 | { 25 | int offset = 0; 26 | offset += serializeAvrFloat64(outbuffer + offset, this->data); 27 | return offset; 28 | } 29 | 30 | virtual int deserialize(unsigned char *inbuffer) 31 | { 32 | int offset = 0; 33 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->data)); 34 | return offset; 35 | } 36 | 37 | const char * getType(){ return "std_msgs/Float64"; }; 38 | const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; 39 | 40 | }; 41 | 42 | } 43 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Int16"; }; 53 | const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Int32"; }; 57 | const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/Int8"; }; 51 | const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 | const char * getType(){ return "std_msgs/String"; }; 50 | const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/UInt16"; }; 42 | const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; }; 43 | 44 | }; 45 | 46 | } 47 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "std_msgs/UInt32"; }; 46 | const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; }; 47 | 48 | }; 49 | 50 | } 51 | #endif -------------------------------------------------------------------------------- /ros_lib/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 24 | { 25 | int offset = 0; 26 | union { 27 | uint64_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) 40 | { 41 | int offset = 0; 42 | union { 43 | uint64_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 | const char * getType(){ return "std_msgs/UInt64"; }; 57 | const char * getMD5(){ return "1b2a79973e8bf53d7b53acb71299cb57"; }; 58 | 59 | }; 60 | 61 | } 62 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | const char * getType(){ return "std_msgs/UInt8"; }; 40 | const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif -------------------------------------------------------------------------------- /ros_lib/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 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | const char * getType(){ return EMPTY; }; 34 | const char * getMD5(){ 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 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | const char * getType(){ return EMPTY; }; 59 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 | -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "tf2_msgs/LookupTransformAction"; }; 51 | const char * getMD5(){ return "7ee01ba91a56c2245c610992dbaa3c37"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "tf2_msgs/LookupTransformActionFeedback"; }; 51 | const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "tf2_msgs/LookupTransformActionGoal"; }; 51 | const char * getMD5(){ return "f2e7bcdb75c847978d0351a13e699da5"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "tf2_msgs/LookupTransformActionResult"; }; 51 | const char * getMD5(){ return "ac26ce75a41384fa8bb4dc10f491ab90"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/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 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "tf2_msgs/LookupTransformFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/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 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) 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 | const char * getType(){ return "tf2_msgs/LookupTransformResult"; }; 45 | const char * getMD5(){ return "3fe5db6a19ca9cfb675418c5ad875c36"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /ros_lib/turtle_actionlib/ShapeAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtle_actionlib_ShapeAction_h 2 | #define _ROS_turtle_actionlib_ShapeAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "turtle_actionlib/ShapeActionGoal.h" 9 | #include "turtle_actionlib/ShapeActionResult.h" 10 | #include "turtle_actionlib/ShapeActionFeedback.h" 11 | 12 | namespace turtle_actionlib 13 | { 14 | 15 | class ShapeAction : public ros::Msg 16 | { 17 | public: 18 | typedef turtle_actionlib::ShapeActionGoal _action_goal_type; 19 | _action_goal_type action_goal; 20 | typedef turtle_actionlib::ShapeActionResult _action_result_type; 21 | _action_result_type action_result; 22 | typedef turtle_actionlib::ShapeActionFeedback _action_feedback_type; 23 | _action_feedback_type action_feedback; 24 | 25 | ShapeAction(): 26 | action_goal(), 27 | action_result(), 28 | action_feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "turtle_actionlib/ShapeAction"; }; 51 | const char * getMD5(){ return "d73b17d6237a925511f5d7727a1dc903"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/turtle_actionlib/ShapeActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtle_actionlib_ShapeActionFeedback_h 2 | #define _ROS_turtle_actionlib_ShapeActionFeedback_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 "turtle_actionlib/ShapeFeedback.h" 11 | 12 | namespace turtle_actionlib 13 | { 14 | 15 | class ShapeActionFeedback : 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 turtle_actionlib::ShapeFeedback _feedback_type; 23 | _feedback_type feedback; 24 | 25 | ShapeActionFeedback(): 26 | header(), 27 | status(), 28 | feedback() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "turtle_actionlib/ShapeActionFeedback"; }; 51 | const char * getMD5(){ return "aae20e09065c3809e8a8e87c4c8953fd"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/turtle_actionlib/ShapeActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtle_actionlib_ShapeActionGoal_h 2 | #define _ROS_turtle_actionlib_ShapeActionGoal_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 "turtle_actionlib/ShapeGoal.h" 11 | 12 | namespace turtle_actionlib 13 | { 14 | 15 | class ShapeActionGoal : 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 turtle_actionlib::ShapeGoal _goal_type; 23 | _goal_type goal; 24 | 25 | ShapeActionGoal(): 26 | header(), 27 | goal_id(), 28 | goal() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "turtle_actionlib/ShapeActionGoal"; }; 51 | const char * getMD5(){ return "dbfccd187f2ec9c593916447ffd6cc77"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/turtle_actionlib/ShapeActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtle_actionlib_ShapeActionResult_h 2 | #define _ROS_turtle_actionlib_ShapeActionResult_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 "turtle_actionlib/ShapeResult.h" 11 | 12 | namespace turtle_actionlib 13 | { 14 | 15 | class ShapeActionResult : 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 turtle_actionlib::ShapeResult _result_type; 23 | _result_type result; 24 | 25 | ShapeActionResult(): 26 | header(), 27 | status(), 28 | result() 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const 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) 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 | const char * getType(){ return "turtle_actionlib/ShapeActionResult"; }; 51 | const char * getMD5(){ return "c8d13d5d140f1047a2e4d3bf5c045822"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /ros_lib/turtle_actionlib/ShapeFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtle_actionlib_ShapeFeedback_h 2 | #define _ROS_turtle_actionlib_ShapeFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace turtle_actionlib 10 | { 11 | 12 | class ShapeFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | ShapeFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "turtle_actionlib/ShapeFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /ros_lib/turtlesim/Color.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_turtlesim_Color_h 2 | #define _ROS_turtlesim_Color_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace turtlesim 10 | { 11 | 12 | class Color : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _r_type; 16 | _r_type r; 17 | typedef uint8_t _g_type; 18 | _g_type g; 19 | typedef uint8_t _b_type; 20 | _b_type b; 21 | 22 | Color(): 23 | r(0), 24 | g(0), 25 | b(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const 30 | { 31 | int offset = 0; 32 | *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF; 33 | offset += sizeof(this->r); 34 | *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF; 35 | offset += sizeof(this->g); 36 | *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF; 37 | offset += sizeof(this->b); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) 42 | { 43 | int offset = 0; 44 | this->r = ((uint8_t) (*(inbuffer + offset))); 45 | offset += sizeof(this->r); 46 | this->g = ((uint8_t) (*(inbuffer + offset))); 47 | offset += sizeof(this->g); 48 | this->b = ((uint8_t) (*(inbuffer + offset))); 49 | offset += sizeof(this->b); 50 | return offset; 51 | } 52 | 53 | const char * getType(){ return "turtlesim/Color"; }; 54 | const char * getMD5(){ return "353891e354491c51aabe32df673fb446"; }; 55 | 56 | }; 57 | 58 | } 59 | #endif -------------------------------------------------------------------------------- /usr/cpp_main.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * cpp_main.c 3 | * 4 | * Created on: Jun 10, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | 8 | #include 9 | #include "main.h" 10 | #include "stm32f1xx_hal.h" 11 | #include "ringbuffer.h" 12 | #include "ros.h" 13 | #include "std_msgs/String.h" 14 | #include "std_msgs/Int16.h" 15 | #include "nbt.h" 16 | #include "geometry_msgs/Twist.h" 17 | 18 | extern uint8_t RxBuffer[RxBufferSize]; 19 | struct ringbuffer rb; 20 | 21 | ros::NodeHandle nh; 22 | std_msgs::String str_msg; 23 | 24 | extern "C" void messageCb(const geometry_msgs::Twist& msg); 25 | ros::Publisher chatter("version", &str_msg); 26 | ros::Subscriber sub("twist_cmd", messageCb); 27 | 28 | static nbt_t publish_nbt; 29 | static nbt_t ros_nbt; 30 | 31 | 32 | extern "C" void messageCb(const geometry_msgs::Twist& msg) 33 | { 34 | //Fill subscriber 35 | } 36 | 37 | extern "C" void cdc_receive_put(uint8_t value) 38 | { 39 | ringbuffer_putchar(&rb, value); 40 | } 41 | 42 | extern "C" void init_ROS() 43 | { 44 | ringbuffer_init(&rb, RxBuffer, RxBufferSize); 45 | 46 | // Initialize ROS 47 | nh.initNode(); 48 | 49 | nh.advertise(chatter); 50 | nh.subscribe(sub); 51 | 52 | NBT_init(&publish_nbt, 500); 53 | NBT_init(&ros_nbt, 10); 54 | } 55 | 56 | extern "C" void version_handler() 57 | { 58 | if (NBT_handler(&publish_nbt)) 59 | { 60 | char version[] = "version: 0.3"; 61 | str_msg.data = version; 62 | chatter.publish(&str_msg); 63 | 64 | } 65 | } 66 | 67 | 68 | extern "C" void spinOnce() 69 | { 70 | if (NBT_handler(&ros_nbt)) 71 | { 72 | nh.spinOnce(); 73 | } 74 | } 75 | 76 | -------------------------------------------------------------------------------- /usr/cpp_main.h: -------------------------------------------------------------------------------- 1 | /* 2 | * cpp_main.h 3 | * 4 | * Created on: Sep 23, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | #ifndef CPP_MAIN_H_ 8 | #define CPP_MAIN_H_ 9 | 10 | #endif /* CPP_MAIN_H_ */ 11 | -------------------------------------------------------------------------------- /usr/ledStatus.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * ledStatus.cpp 3 | * 4 | * Created on: Sep 23, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | 8 | #include "stm32f1xx_hal.h" 9 | #include "nbt.h" 10 | 11 | static nbt_t lednbt; 12 | 13 | extern "C" void init_ledStatus() 14 | { 15 | NBT_init(&lednbt, 500); 16 | } 17 | 18 | extern "C" void ledStatus_handler() 19 | { 20 | if (NBT_handler(&lednbt)) 21 | { 22 | HAL_GPIO_TogglePin(LED_GPIO_Port, LED_Pin); 23 | } 24 | } 25 | -------------------------------------------------------------------------------- /usr/ledStatus.h: -------------------------------------------------------------------------------- 1 | /* 2 | * ledStatus.h 3 | * 4 | * Created on: Sep 23, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | 8 | #ifndef LEDSTATUS_H_ 9 | #define LEDSTATUS_H_ 10 | 11 | #endif /* LEDSTATUS_H_ */ 12 | -------------------------------------------------------------------------------- /usr/nbt.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * non_blocking_timer.c 3 | * 4 | * Created on: Jun 10, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | 8 | #include "stm32f1xx_hal.h" 9 | #include "nbt.h" 10 | 11 | //NBT - Non Blocking Timer 12 | void NBT_init(nbt_t * nbt, uint32_t interval) 13 | { 14 | nbt->timeout = interval; 15 | nbt->previousMillis = HAL_GetTick(); 16 | } 17 | 18 | bool NBT_handler(nbt_t * nbt) 19 | { 20 | if(HAL_GetTick()-nbt->previousMillis>nbt->timeout){ 21 | nbt->previousMillis = HAL_GetTick(); 22 | return true; 23 | } 24 | 25 | return false; 26 | } 27 | 28 | 29 | -------------------------------------------------------------------------------- /usr/nbt.h: -------------------------------------------------------------------------------- 1 | /* 2 | * nbt.h 3 | * 4 | * Created on: Jun 10, 2018 5 | * Author: Itamar Eliakim 6 | */ 7 | 8 | #ifndef NBT_H_ 9 | #define NBT_H_ 10 | #include "main.h" 11 | #include "stm32f1xx_hal.h" 12 | #include 13 | 14 | typedef struct{ 15 | uint32_t timeout; 16 | uint32_t previousMillis; 17 | 18 | }nbt_t; 19 | 20 | void NBT_init(nbt_t * nbt, uint32_t interval); 21 | bool NBT_handler(nbt_t * nbt); 22 | 23 | 24 | #endif /* NBT_H_ */ 25 | --------------------------------------------------------------------------------