├── Dockerfile ├── examples ├── ADC │ └── ADC.pde ├── Blink │ └── Blink.pde ├── BlinkM │ ├── BlinkM.pde │ └── BlinkM_funcs.h ├── BlinkerWithClass │ └── BlinkerWithClass.ino ├── Clapper │ └── Clapper.pde ├── Esp8266 │ └── Esp8266.ino ├── 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 ├── WiFiNINAHelloWorld │ └── WiFiNINAHelloWorld.ino ├── button_example │ └── button_example.pde └── pubsub │ └── pubsub.pde ├── extras └── tests │ ├── array_test │ └── array_test.pde │ ├── float64_test │ └── float64_test.pde │ └── time_test │ └── time_test.pde ├── keywords.txt ├── library.properties ├── readme.md ├── scripts └── esp8266_pstr_fix.py ├── src ├── ArduinoHardware.h ├── ArduinoIncludes.h ├── ArduinoTcpHardware.h ├── Esp32Hardware.h ├── Esp8266Hardware.h ├── MKR1000Hardware.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 ├── control_toolbox │ └── SetPidGains.h ├── controller_manager_msgs │ ├── ControllerState.h │ ├── ControllerStatistics.h │ ├── ControllersStatistics.h │ ├── HardwareInterfaceResources.h │ ├── ListControllerTypes.h │ ├── ListControllers.h │ ├── LoadController.h │ ├── ReloadControllerLibraries.h │ ├── SwitchController.h │ └── UnloadController.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 ├── 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 ├── gps_common │ ├── GPSFix.h │ └── GPSStatus.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 ├── nav_msgs │ ├── GetMap.h │ ├── GetMapAction.h │ ├── GetMapActionFeedback.h │ ├── GetMapActionGoal.h │ ├── GetMapActionResult.h │ ├── GetMapFeedback.h │ ├── GetMapGoal.h │ ├── GetMapResult.h │ ├── GetPlan.h │ ├── GridCells.h │ ├── MapMetaData.h │ ├── OccupancyGrid.h │ ├── Odometry.h │ ├── Path.h │ └── SetMap.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_mbed │ ├── 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 ├── 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 └── update.sh /Dockerfile: -------------------------------------------------------------------------------- 1 | FROM ros:noetic-ros-base 2 | 3 | RUN apt-get update &&\ 4 | apt-get install -y ros-$ROS_DISTRO-rosserial-arduino ros-$ROS_DISTRO-rosserial git &&\ 5 | apt-get -y clean &&\ 6 | apt-get -y purge &&\ 7 | rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* 8 | 9 | # Create a Catkin Workspace 10 | SHELL ["/bin/bash", "-c"] 11 | ENV CATKIN_WS /catkin_ws 12 | RUN source /opt/ros/$ROS_DISTRO/setup.bash &&\ 13 | mkdir -p $CATKIN_WS/src &&\ 14 | cd $CATKIN_WS/ &&\ 15 | catkin_make 16 | 17 | # Build ROS Serial 18 | RUN source /opt/ros/$ROS_DISTRO/setup.bash &&\ 19 | cd $CATKIN_WS/src &&\ 20 | git clone https://github.com/ros-drivers/rosserial.git &&\ 21 | cd $CATKIN_WS &&\ 22 | catkin_make &&\ 23 | catkin_make install 24 | 25 | # Create ROS Serial Arduino builder 26 | RUN source /opt/ros/$ROS_DISTRO/setup.bash &&\ 27 | cd /tmp &&\ 28 | rosrun rosserial_arduino make_libraries.py . 29 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /examples/Blink/Blink.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Subscriber Example 3 | * Blinks an LED on callback 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | 11 | void messageCb( const std_msgs::Empty& toggle_msg){ 12 | digitalWrite(LED_BUILTIN, HIGH-digitalRead(LED_BUILTIN)); // blink the led 13 | } 14 | 15 | ros::Subscriber sub("toggle_led", &messageCb ); 16 | 17 | void setup() 18 | { 19 | pinMode(LED_BUILTIN, OUTPUT); 20 | nh.initNode(); 21 | nh.subscribe(sub); 22 | } 23 | 24 | void loop() 25 | { 26 | nh.spinOnce(); 27 | delay(1); 28 | } 29 | 30 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /examples/Esp8266/Esp8266.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | * This intend to connect to a Wifi Access Point 5 | * and a rosserial socket server. 6 | * You can launch the rosserial socket server with 7 | * roslaunch rosserial_server socket.launch 8 | * The default port is 11411 9 | * 10 | */ 11 | #include 12 | #include 13 | #include 14 | 15 | const char* ssid = "your-ssid"; 16 | const char* password = "your-password"; 17 | // Set the rosserial socket server IP address 18 | IPAddress server(192,168,1,1); 19 | // Set the rosserial socket server port 20 | const uint16_t serverPort = 11411; 21 | 22 | ros::NodeHandle nh; 23 | // Make a chatter publisher 24 | std_msgs::String str_msg; 25 | ros::Publisher chatter("chatter", &str_msg); 26 | 27 | // Be polite and say hello 28 | char hello[13] = "hello world!"; 29 | 30 | void setup() 31 | { 32 | // Use ESP8266 serial to monitor the process 33 | Serial.begin(115200); 34 | Serial.println(); 35 | Serial.print("Connecting to "); 36 | Serial.println(ssid); 37 | 38 | // Connect the ESP8266 the the wifi AP 39 | WiFi.begin(ssid, password); 40 | while (WiFi.status() != WL_CONNECTED) { 41 | delay(500); 42 | Serial.print("."); 43 | } 44 | Serial.println(""); 45 | Serial.println("WiFi connected"); 46 | Serial.println("IP address: "); 47 | Serial.println(WiFi.localIP()); 48 | 49 | // Set the connection to rosserial socket server 50 | nh.getHardware()->setConnection(server, serverPort); 51 | nh.initNode(); 52 | 53 | // Another way to get IP 54 | Serial.print("IP = "); 55 | Serial.println(nh.getHardware()->getLocalIP()); 56 | 57 | // Start to be polite 58 | nh.advertise(chatter); 59 | } 60 | 61 | void loop() 62 | { 63 | 64 | if (nh.connected()) { 65 | Serial.println("Connected"); 66 | // Say hello 67 | str_msg.data = hello; 68 | chatter.publish( &str_msg ); 69 | } else { 70 | Serial.println("Not Connected"); 71 | } 72 | nh.spinOnce(); 73 | // Loop exproximativly at 1Hz 74 | delay(1000); 75 | } 76 | -------------------------------------------------------------------------------- /examples/Esp8266HelloWorld/Esp8266HelloWorld.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | * This intend to connect to a Wifi Access Point 5 | * and a rosserial socket server. 6 | * You can launch the rosserial socket server with 7 | * roslaunch rosserial_server socket.launch 8 | * The default port is 11411 9 | * 10 | */ 11 | #include 12 | #include 13 | #include 14 | 15 | const char* ssid = "your-ssid"; 16 | const char* password = "your-password"; 17 | // Set the rosserial socket server IP address 18 | IPAddress server(192,168,1,1); 19 | // Set the rosserial socket server port 20 | const uint16_t serverPort = 11411; 21 | 22 | ros::NodeHandle nh; 23 | // Make a chatter publisher 24 | std_msgs::String str_msg; 25 | ros::Publisher chatter("chatter", &str_msg); 26 | 27 | // Be polite and say hello 28 | char hello[13] = "hello world!"; 29 | 30 | void setup() 31 | { 32 | // Use ESP8266 serial to monitor the process 33 | Serial.begin(115200); 34 | Serial.println(); 35 | Serial.print("Connecting to "); 36 | Serial.println(ssid); 37 | 38 | // Connect the ESP8266 the the wifi AP 39 | WiFi.begin(ssid, password); 40 | while (WiFi.status() != WL_CONNECTED) { 41 | delay(500); 42 | Serial.print("."); 43 | } 44 | Serial.println(""); 45 | Serial.println("WiFi connected"); 46 | Serial.println("IP address: "); 47 | Serial.println(WiFi.localIP()); 48 | 49 | // Set the connection to rosserial socket server 50 | nh.getHardware()->setConnection(server, serverPort); 51 | nh.initNode(); 52 | 53 | // Another way to get IP 54 | Serial.print("IP = "); 55 | Serial.println(nh.getHardware()->getLocalIP()); 56 | 57 | // Start to be polite 58 | nh.advertise(chatter); 59 | } 60 | 61 | void loop() 62 | { 63 | 64 | if (nh.connected()) { 65 | Serial.println("Connected"); 66 | // Say hello 67 | str_msg.data = hello; 68 | chatter.publish( &str_msg ); 69 | } else { 70 | Serial.println("Not Connected"); 71 | } 72 | nh.spinOnce(); 73 | // Loop exproximativly at 1Hz 74 | delay(1000); 75 | } 76 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /examples/WiFiNINAHelloWorld/WiFiNINAHelloWorld.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | * This intend to connect to a Wifi Access Point 5 | * and a rosserial socket server. 6 | * You can launch the rosserial socket server with 7 | * roslaunch rosserial_server socket.launch 8 | * The default port is 11411 9 | * 10 | */ 11 | #include 12 | #include 13 | #include 14 | 15 | const char* ssid = "your-ssid"; 16 | const char* password = "your-password"; 17 | // Set the rosserial socket server IP address (likely ROS_IP) 18 | IPAddress server(192,168,1,1); 19 | // Set the rosserial socket server port 20 | const uint16_t serverPort = 11411; 21 | 22 | ros::NodeHandle nh; 23 | // Make a chatter publisher 24 | std_msgs::String str_msg; 25 | ros::Publisher chatter("chatter", &str_msg); 26 | 27 | // Be polite and say hello 28 | char hello[13] = "hello world!"; 29 | 30 | void setup() 31 | { 32 | // Use Arduino serial to monitor the process 33 | Serial.begin(9600); 34 | Serial.println(); 35 | Serial.print("Connecting to "); 36 | Serial.println(ssid); 37 | 38 | // Connect the WiFiNINA compatible board to the wifi AP 39 | WiFi.begin(ssid, password); 40 | while (WiFi.status() != WL_CONNECTED) { 41 | delay(500); 42 | Serial.print("."); 43 | } 44 | Serial.println(""); 45 | Serial.println("WiFi connected"); 46 | Serial.println("IP address: "); 47 | Serial.println(WiFi.localIP()); 48 | 49 | // Set the connection to rosserial socket server 50 | nh.getHardware()->setConnection(server, serverPort); 51 | nh.initNode(); 52 | 53 | // Another way to get IP 54 | Serial.print("IP = "); 55 | Serial.println(nh.getHardware()->getLocalIP()); 56 | 57 | // Start to be polite 58 | nh.advertise(chatter); 59 | } 60 | 61 | void loop() 62 | { 63 | if (nh.connected()) { 64 | Serial.println("Connected"); 65 | // Say hello 66 | str_msg.data = hello; 67 | chatter.publish( &str_msg ); 68 | } else { 69 | Serial.println("Not Connected"); 70 | } 71 | nh.spinOnce(); 72 | // Loop at ~1Hz 73 | delay(1000); 74 | } 75 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /extras/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 | -------------------------------------------------------------------------------- /extras/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 | -------------------------------------------------------------------------------- /extras/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 | -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For Rosserial 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | Test KEYWORD1 10 | 11 | ####################################### 12 | # Methods and Functions (KEYWORD2) 13 | ####################################### 14 | 15 | doSomething KEYWORD2 16 | 17 | ####################################### 18 | # Instances (KEYWORD2) 19 | ####################################### 20 | 21 | ####################################### 22 | # Constants (LITERAL1) 23 | ####################################### 24 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=Rosserial Arduino Library 2 | version=0.9.1 3 | author=Michael Ferguson 4 | maintainer=Joshua Frank 5 | sentence=Use an Arduino as a ROS publisher/subscriber 6 | paragraph=Works with http://wiki.ros.org/rosserial, requires a rosserial node to connect 7 | category=Communication 8 | url=https://github.com/frankjoshua/rosserial_arduino_lib 9 | architectures=* 10 | includes=ros.h 11 | -------------------------------------------------------------------------------- /readme.md: -------------------------------------------------------------------------------- 1 | # ROS Serial Arduino library 2 | 3 | ## Purpose 4 | 5 | Installing ROS Serial library into and Arduino IDE can be an involved task. See instructions http://wiki.ros.org/rosserial. If you don't already have ROS installed on your workstation it's difficult to build due to the Catkin workspace requirement. This repo packages the library for the Arduino IDE and PlatformIO in an expected format. 6 | 7 | ## ROS Serial Description 8 | 9 | rosserial is a protocol for wrapping standard ROS serialized messages and multiplexing multiple topics and services over a character device such as a serial port or network socket. 10 | 11 | Use an Arduino as a ROS publisher/subscriber 12 | 13 | Works with http://wiki.ros.org/rosserial, requires a rosserial node to connect 14 | 15 | ## Updating 16 | 17 | There is a script to pull in the current changes from https://github.com/ros-drivers/rosserial. It creates a Docker container with ROS and Catkin setup. It then downloads the current version of ROS Serial from Github and builds the libraries. Finally it overwrites the current src files with the new build. Currently there is no automatic testing. So it must be manually tested (to involved to discuss here). 18 | 19 | ``` 20 | ./update.sh 21 | ``` 22 | 23 | ## Reporting issues 24 | 25 | If this repo is out of date feel free to report an issue. However pull requests should be directed to https://github.com/ros-drivers/rosserial. Any changes to this repo would be overwritten by incoming changes from upstream. 26 | 27 | ## License 28 | 29 | Apache 2.0 30 | 31 | ## Author Information 32 | 33 | Joshua Frank [@frankjoshua77](https://www.twitter.com/@frankjoshua77) 34 |
35 | [http://roboticsascode.com](http://roboticsascode.com) 36 | -------------------------------------------------------------------------------- /src/actionlib/TestAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestAction_h 2 | #define _ROS_actionlib_TestAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "actionlib/TestActionGoal.h" 9 | #include "actionlib/TestActionResult.h" 10 | #include "actionlib/TestActionFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestAction_type[] PROGMEM= "actionlib/TestAction"; 16 | static const char actionlib_TestAction_md5[] PROGMEM= "991e87a72802262dfbe5d1b3cf6efc9a"; 17 | class TestAction : public ros::Msg 18 | { 19 | public: 20 | typedef actionlib::TestActionGoal _action_goal_type; 21 | _action_goal_type action_goal; 22 | typedef actionlib::TestActionResult _action_result_type; 23 | _action_result_type action_result; 24 | typedef actionlib::TestActionFeedback _action_feedback_type; 25 | _action_feedback_type action_feedback; 26 | 27 | TestAction(): 28 | action_goal(), 29 | action_result(), 30 | action_feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->action_goal.serialize(outbuffer + offset); 38 | offset += this->action_result.serialize(outbuffer + offset); 39 | offset += this->action_feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->action_goal.deserialize(inbuffer + offset); 47 | offset += this->action_result.deserialize(inbuffer + offset); 48 | offset += this->action_feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestAction_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestAction_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionFeedback_h 2 | #define _ROS_actionlib_TestActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestActionFeedback_type[] PROGMEM= "actionlib/TestActionFeedback"; 16 | static const char actionlib_TestActionFeedback_md5[] PROGMEM= "6d3d0bf7fb3dda24779c010a9f3eb7cb"; 17 | class TestActionFeedback : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TestFeedback _feedback_type; 25 | _feedback_type feedback; 26 | 27 | TestActionFeedback(): 28 | header(), 29 | status(), 30 | feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestActionFeedback_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestActionFeedback_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionGoal_h 2 | #define _ROS_actionlib_TestActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TestGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestActionGoal_type[] PROGMEM= "actionlib/TestActionGoal"; 16 | static const char actionlib_TestActionGoal_md5[] PROGMEM= "348369c5b403676156094e8c159720bf"; 17 | class TestActionGoal : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalID _goal_id_type; 23 | _goal_id_type goal_id; 24 | typedef actionlib::TestGoal _goal_type; 25 | _goal_type goal; 26 | 27 | TestActionGoal(): 28 | header(), 29 | goal_id(), 30 | goal() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->goal_id.serialize(outbuffer + offset); 39 | offset += this->goal.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->goal_id.deserialize(inbuffer + offset); 48 | offset += this->goal.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestActionGoal_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestActionGoal_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestActionResult_h 2 | #define _ROS_actionlib_TestActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestActionResult_type[] PROGMEM= "actionlib/TestActionResult"; 16 | static const char actionlib_TestActionResult_md5[] PROGMEM= "3d669e3a63aa986c667ea7b0f46ce85e"; 17 | class TestActionResult : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TestResult _result_type; 25 | _result_type result; 26 | 27 | TestActionResult(): 28 | header(), 29 | status(), 30 | result() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->result.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->result.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestActionResult_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestActionResult_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionFeedback_h 2 | #define _ROS_actionlib_TestRequestActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestRequestFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestRequestActionFeedback_type[] PROGMEM= "actionlib/TestRequestActionFeedback"; 16 | static const char actionlib_TestRequestActionFeedback_md5[] PROGMEM= "aae20e09065c3809e8a8e87c4c8953fd"; 17 | class TestRequestActionFeedback : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TestRequestFeedback _feedback_type; 25 | _feedback_type feedback; 26 | 27 | TestRequestActionFeedback(): 28 | header(), 29 | status(), 30 | feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestRequestActionFeedback_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestRequestActionFeedback_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionGoal_h 2 | #define _ROS_actionlib_TestRequestActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TestRequestGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestRequestActionGoal_type[] PROGMEM= "actionlib/TestRequestActionGoal"; 16 | static const char actionlib_TestRequestActionGoal_md5[] PROGMEM= "1889556d3fef88f821c7cb004e4251f3"; 17 | class TestRequestActionGoal : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalID _goal_id_type; 23 | _goal_id_type goal_id; 24 | typedef actionlib::TestRequestGoal _goal_type; 25 | _goal_type goal; 26 | 27 | TestRequestActionGoal(): 28 | header(), 29 | goal_id(), 30 | goal() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->goal_id.serialize(outbuffer + offset); 39 | offset += this->goal.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->goal_id.deserialize(inbuffer + offset); 48 | offset += this->goal.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestRequestActionGoal_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestRequestActionGoal_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestActionResult_h 2 | #define _ROS_actionlib_TestRequestActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TestRequestResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TestRequestActionResult_type[] PROGMEM= "actionlib/TestRequestActionResult"; 16 | static const char actionlib_TestRequestActionResult_md5[] PROGMEM= "0476d1fdf437a3a6e7d6d0e9f5561298"; 17 | class TestRequestActionResult : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TestRequestResult _result_type; 25 | _result_type result; 26 | 27 | TestRequestActionResult(): 28 | header(), 29 | status(), 30 | result() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->result.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->result.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestRequestActionResult_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestRequestActionResult_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TestRequestFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestFeedback_h 2 | #define _ROS_actionlib_TestRequestFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | static const char actionlib_TestRequestFeedback_type[] PROGMEM= "actionlib/TestRequestFeedback"; 13 | static const char actionlib_TestRequestFeedback_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class TestRequestFeedback : public ros::Msg 15 | { 16 | public: 17 | 18 | TestRequestFeedback() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TestRequestFeedback_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TestRequestFeedback_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionFeedback_h 2 | #define _ROS_actionlib_TwoIntsActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TwoIntsFeedback.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TwoIntsActionFeedback_type[] PROGMEM= "actionlib/TwoIntsActionFeedback"; 16 | static const char actionlib_TwoIntsActionFeedback_md5[] PROGMEM= "aae20e09065c3809e8a8e87c4c8953fd"; 17 | class TwoIntsActionFeedback : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TwoIntsFeedback _feedback_type; 25 | _feedback_type feedback; 26 | 27 | TwoIntsActionFeedback(): 28 | header(), 29 | status(), 30 | feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TwoIntsActionFeedback_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TwoIntsActionFeedback_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionGoal_h 2 | #define _ROS_actionlib_TwoIntsActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "actionlib/TwoIntsGoal.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TwoIntsActionGoal_type[] PROGMEM= "actionlib/TwoIntsActionGoal"; 16 | static const char actionlib_TwoIntsActionGoal_md5[] PROGMEM= "684a2db55d6ffb8046fb9d6764ce0860"; 17 | class TwoIntsActionGoal : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalID _goal_id_type; 23 | _goal_id_type goal_id; 24 | typedef actionlib::TwoIntsGoal _goal_type; 25 | _goal_type goal; 26 | 27 | TwoIntsActionGoal(): 28 | header(), 29 | goal_id(), 30 | goal() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->goal_id.serialize(outbuffer + offset); 39 | offset += this->goal.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->goal_id.deserialize(inbuffer + offset); 48 | offset += this->goal.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TwoIntsActionGoal_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TwoIntsActionGoal_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsActionResult_h 2 | #define _ROS_actionlib_TwoIntsActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "actionlib/TwoIntsResult.h" 11 | 12 | namespace actionlib 13 | { 14 | 15 | static const char actionlib_TwoIntsActionResult_type[] PROGMEM= "actionlib/TwoIntsActionResult"; 16 | static const char actionlib_TwoIntsActionResult_md5[] PROGMEM= "3ba7dea8b8cddcae4528ade4ef74b6e7"; 17 | class TwoIntsActionResult : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef actionlib::TwoIntsResult _result_type; 25 | _result_type result; 26 | 27 | TwoIntsActionResult(): 28 | header(), 29 | status(), 30 | result() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->result.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->result.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TwoIntsActionResult_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TwoIntsActionResult_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/actionlib/TwoIntsFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsFeedback_h 2 | #define _ROS_actionlib_TwoIntsFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | static const char actionlib_TwoIntsFeedback_type[] PROGMEM= "actionlib/TwoIntsFeedback"; 13 | static const char actionlib_TwoIntsFeedback_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class TwoIntsFeedback : public ros::Msg 15 | { 16 | public: 17 | 18 | TwoIntsFeedback() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)actionlib_TwoIntsFeedback_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)actionlib_TwoIntsFeedback_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "actionlib_tutorials/AveragingFeedback.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class AveragingActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef actionlib_tutorials::AveragingFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | AveragingActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/AveragingActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/AveragingActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("78a4a09241b1791069223ae7ebd5b16b");}; 58 | #else 59 | const char * getMD5() { return PSTR("78a4a09241b1791069223ae7ebd5b16b");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "actionlib_tutorials/AveragingGoal.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class AveragingActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef actionlib_tutorials::AveragingGoal _goal_type; 24 | _goal_type goal; 25 | 26 | AveragingActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/AveragingActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/AveragingActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("1561825b734ebd6039851c501e3fb570");}; 58 | #else 59 | const char * getMD5() { return PSTR("1561825b734ebd6039851c501e3fb570");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "actionlib_tutorials/AveragingResult.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class AveragingActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef actionlib_tutorials::AveragingResult _result_type; 24 | _result_type result; 25 | 26 | AveragingActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/AveragingActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/AveragingActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("8672cb489d347580acdcd05c5d497497");}; 58 | #else 59 | const char * getMD5() { return PSTR("8672cb489d347580acdcd05c5d497497");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "actionlib_tutorials/FibonacciFeedback.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class FibonacciActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef actionlib_tutorials::FibonacciFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | FibonacciActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/FibonacciActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/FibonacciActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("73b8497a9f629a31c0020900e4148f07");}; 58 | #else 59 | const char * getMD5() { return PSTR("73b8497a9f629a31c0020900e4148f07");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "actionlib_tutorials/FibonacciGoal.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class FibonacciActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef actionlib_tutorials::FibonacciGoal _goal_type; 24 | _goal_type goal; 25 | 26 | FibonacciActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/FibonacciActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/FibonacciActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("006871c7fa1d0e3d5fe2226bf17b2a94");}; 58 | #else 59 | const char * getMD5() { return PSTR("006871c7fa1d0e3d5fe2226bf17b2a94");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "actionlib_tutorials/FibonacciResult.h" 12 | 13 | namespace actionlib_tutorials 14 | { 15 | 16 | class FibonacciActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef actionlib_tutorials::FibonacciResult _result_type; 24 | _result_type result; 25 | 26 | FibonacciActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("actionlib_tutorials/FibonacciActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("actionlib_tutorials/FibonacciActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("bee73a9fe29ae25e966e105f5553dd03");}; 58 | #else 59 | const char * getMD5() { return PSTR("bee73a9fe29ae25e966e105f5553dd03");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/bond/Constants.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_bond_Constants_h 2 | #define _ROS_bond_Constants_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace bond 10 | { 11 | 12 | static const char bond_Constants_type[] PROGMEM= "bond/Constants"; 13 | static const char bond_Constants_md5[] PROGMEM= "6fc594dc1d7bd7919077042712f8c8b0"; 14 | class Constants : public ros::Msg 15 | { 16 | public: 17 | enum { DEAD_PUBLISH_PERIOD = 0.05 }; 18 | enum { DEFAULT_CONNECT_TIMEOUT = 10.0 }; 19 | enum { DEFAULT_HEARTBEAT_TIMEOUT = 4.0 }; 20 | enum { DEFAULT_DISCONNECT_TIMEOUT = 2.0 }; 21 | enum { DEFAULT_HEARTBEAT_PERIOD = 1.0 }; 22 | enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout }; 23 | 24 | Constants() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) override 35 | { 36 | int offset = 0; 37 | return offset; 38 | } 39 | 40 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)bond_Constants_type);return type_msg; }; 41 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)bond_Constants_md5);return md5_msg; }; 42 | 43 | }; 44 | 45 | } 46 | #endif 47 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "control_msgs/FollowJointTrajectoryGoal.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class FollowJointTrajectoryActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef control_msgs::FollowJointTrajectoryGoal _goal_type; 24 | _goal_type goal; 25 | 26 | FollowJointTrajectoryActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/FollowJointTrajectoryActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/FollowJointTrajectoryActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("cff5c1d533bf2f82dd0138d57f4304bb");}; 58 | #else 59 | const char * getMD5() { return PSTR("cff5c1d533bf2f82dd0138d57f4304bb");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/FollowJointTrajectoryResult.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class FollowJointTrajectoryActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::FollowJointTrajectoryResult _result_type; 24 | _result_type result; 25 | 26 | FollowJointTrajectoryActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/FollowJointTrajectoryActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/FollowJointTrajectoryActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("c4fb3b000dc9da4fd99699380efcc5d9");}; 58 | #else 59 | const char * getMD5() { return PSTR("c4fb3b000dc9da4fd99699380efcc5d9");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class GripperCommand : public ros::Msg 14 | { 15 | public: 16 | typedef float _position_type; 17 | _position_type position; 18 | typedef float _max_effort_type; 19 | _max_effort_type max_effort; 20 | 21 | GripperCommand(): 22 | position(0), 23 | max_effort(0) 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const 28 | { 29 | int offset = 0; 30 | offset += serializeAvrFloat64(outbuffer + offset, this->position); 31 | offset += serializeAvrFloat64(outbuffer + offset, this->max_effort); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) 36 | { 37 | int offset = 0; 38 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); 39 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_effort)); 40 | return offset; 41 | } 42 | 43 | #ifdef ESP8266 44 | const char * getType() { return ("control_msgs/GripperCommand");}; 45 | #else 46 | const char * getType() { return PSTR("control_msgs/GripperCommand");}; 47 | #endif 48 | #ifdef ESP8266 49 | const char * getMD5() { return ("680acaff79486f017132a7f198d40f08");}; 50 | #else 51 | const char * getMD5() { return PSTR("680acaff79486f017132a7f198d40f08");}; 52 | #endif 53 | 54 | }; 55 | 56 | } 57 | #endif 58 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/GripperCommandFeedback.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class GripperCommandActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::GripperCommandFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | GripperCommandActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/GripperCommandActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/GripperCommandActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("653dff30c045f5e6ff3feb3409f4558d");}; 58 | #else 59 | const char * getMD5() { return PSTR("653dff30c045f5e6ff3feb3409f4558d");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "control_msgs/GripperCommandGoal.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class GripperCommandActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef control_msgs::GripperCommandGoal _goal_type; 24 | _goal_type goal; 25 | 26 | GripperCommandActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/GripperCommandActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/GripperCommandActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("aa581f648a35ed681db2ec0bf7a82bea");}; 58 | #else 59 | const char * getMD5() { return PSTR("aa581f648a35ed681db2ec0bf7a82bea");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/GripperCommandResult.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class GripperCommandActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::GripperCommandResult _result_type; 24 | _result_type result; 25 | 26 | GripperCommandActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/GripperCommandActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/GripperCommandActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("143702cb2df0f163c5283cedc5efc6b6");}; 58 | #else 59 | const char * getMD5() { return PSTR("143702cb2df0f163c5283cedc5efc6b6");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "control_msgs/GripperCommand.h" 10 | 11 | namespace control_msgs 12 | { 13 | 14 | class GripperCommandGoal : public ros::Msg 15 | { 16 | public: 17 | typedef control_msgs::GripperCommand _command_type; 18 | _command_type command; 19 | 20 | GripperCommandGoal(): 21 | command() 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const 26 | { 27 | int offset = 0; 28 | offset += this->command.serialize(outbuffer + offset); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | offset += this->command.deserialize(inbuffer + offset); 36 | return offset; 37 | } 38 | 39 | #ifdef ESP8266 40 | const char * getType() { return ("control_msgs/GripperCommandGoal");}; 41 | #else 42 | const char * getType() { return PSTR("control_msgs/GripperCommandGoal");}; 43 | #endif 44 | #ifdef ESP8266 45 | const char * getMD5() { return ("86fd82f4ddc48a4cb6856cfa69217e43");}; 46 | #else 47 | const char * getMD5() { return PSTR("86fd82f4ddc48a4cb6856cfa69217e43");}; 48 | #endif 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/JointTrajectoryFeedback.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class JointTrajectoryActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::JointTrajectoryFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | JointTrajectoryActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/JointTrajectoryActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/JointTrajectoryActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("aae20e09065c3809e8a8e87c4c8953fd");}; 58 | #else 59 | const char * getMD5() { return PSTR("aae20e09065c3809e8a8e87c4c8953fd");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "control_msgs/JointTrajectoryGoal.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class JointTrajectoryActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef control_msgs::JointTrajectoryGoal _goal_type; 24 | _goal_type goal; 25 | 26 | JointTrajectoryActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/JointTrajectoryActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/JointTrajectoryActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("a99e83ef6185f9fdd7693efe99623a86");}; 58 | #else 59 | const char * getMD5() { return PSTR("a99e83ef6185f9fdd7693efe99623a86");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/JointTrajectoryResult.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class JointTrajectoryActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::JointTrajectoryResult _result_type; 24 | _result_type result; 25 | 26 | JointTrajectoryActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/JointTrajectoryActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/JointTrajectoryActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("1eb06eeff08fa7ea874431638cb52332");}; 58 | #else 59 | const char * getMD5() { return PSTR("1eb06eeff08fa7ea874431638cb52332");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class JointTrajectoryFeedback : public ros::Msg 14 | { 15 | public: 16 | 17 | JointTrajectoryFeedback() 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 | #ifdef ESP8266 34 | const char * getType() { return ("control_msgs/JointTrajectoryFeedback");}; 35 | #else 36 | const char * getType() { return PSTR("control_msgs/JointTrajectoryFeedback");}; 37 | #endif 38 | #ifdef ESP8266 39 | const char * getMD5() { return ("d41d8cd98f00b204e9800998ecf8427e");}; 40 | #else 41 | const char * getMD5() { return PSTR("d41d8cd98f00b204e9800998ecf8427e");}; 42 | #endif 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "trajectory_msgs/JointTrajectory.h" 10 | 11 | namespace control_msgs 12 | { 13 | 14 | class JointTrajectoryGoal : public ros::Msg 15 | { 16 | public: 17 | typedef trajectory_msgs::JointTrajectory _trajectory_type; 18 | _trajectory_type trajectory; 19 | 20 | JointTrajectoryGoal(): 21 | trajectory() 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const 26 | { 27 | int offset = 0; 28 | offset += this->trajectory.serialize(outbuffer + offset); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | offset += this->trajectory.deserialize(inbuffer + offset); 36 | return offset; 37 | } 38 | 39 | #ifdef ESP8266 40 | const char * getType() { return ("control_msgs/JointTrajectoryGoal");}; 41 | #else 42 | const char * getType() { return PSTR("control_msgs/JointTrajectoryGoal");}; 43 | #endif 44 | #ifdef ESP8266 45 | const char * getMD5() { return ("2a0eff76c870e8595636c2a562ca298e");}; 46 | #else 47 | const char * getMD5() { return PSTR("2a0eff76c870e8595636c2a562ca298e");}; 48 | #endif 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class JointTrajectoryResult : public ros::Msg 14 | { 15 | public: 16 | 17 | JointTrajectoryResult() 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 | #ifdef ESP8266 34 | const char * getType() { return ("control_msgs/JointTrajectoryResult");}; 35 | #else 36 | const char * getType() { return PSTR("control_msgs/JointTrajectoryResult");}; 37 | #endif 38 | #ifdef ESP8266 39 | const char * getMD5() { return ("d41d8cd98f00b204e9800998ecf8427e");}; 40 | #else 41 | const char * getMD5() { return PSTR("d41d8cd98f00b204e9800998ecf8427e");}; 42 | #endif 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/PointHeadFeedback.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class PointHeadActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::PointHeadFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | PointHeadActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/PointHeadActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/PointHeadActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("33c9244957176bbba97dd641119e8460");}; 58 | #else 59 | const char * getMD5() { return PSTR("33c9244957176bbba97dd641119e8460");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "control_msgs/PointHeadGoal.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class PointHeadActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef control_msgs::PointHeadGoal _goal_type; 24 | _goal_type goal; 25 | 26 | PointHeadActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/PointHeadActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/PointHeadActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("b53a8323d0ba7b310ba17a2d3a82a6b8");}; 58 | #else 59 | const char * getMD5() { return PSTR("b53a8323d0ba7b310ba17a2d3a82a6b8");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/PointHeadResult.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class PointHeadActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::PointHeadResult _result_type; 24 | _result_type result; 25 | 26 | PointHeadActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/PointHeadActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/PointHeadActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("1eb06eeff08fa7ea874431638cb52332");}; 58 | #else 59 | const char * getMD5() { return PSTR("1eb06eeff08fa7ea874431638cb52332");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class PointHeadFeedback : public ros::Msg 14 | { 15 | public: 16 | typedef float _pointing_angle_error_type; 17 | _pointing_angle_error_type pointing_angle_error; 18 | 19 | PointHeadFeedback(): 20 | pointing_angle_error(0) 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += serializeAvrFloat64(outbuffer + offset, this->pointing_angle_error); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->pointing_angle_error)); 35 | return offset; 36 | } 37 | 38 | #ifdef ESP8266 39 | const char * getType() { return ("control_msgs/PointHeadFeedback");}; 40 | #else 41 | const char * getType() { return PSTR("control_msgs/PointHeadFeedback");}; 42 | #endif 43 | #ifdef ESP8266 44 | const char * getMD5() { return ("cce80d27fd763682da8805a73316cab4");}; 45 | #else 46 | const char * getMD5() { return PSTR("cce80d27fd763682da8805a73316cab4");}; 47 | #endif 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class PointHeadResult : public ros::Msg 14 | { 15 | public: 16 | 17 | PointHeadResult() 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 | #ifdef ESP8266 34 | const char * getType() { return ("control_msgs/PointHeadResult");}; 35 | #else 36 | const char * getType() { return PSTR("control_msgs/PointHeadResult");}; 37 | #endif 38 | #ifdef ESP8266 39 | const char * getMD5() { return ("d41d8cd98f00b204e9800998ecf8427e");}; 40 | #else 41 | const char * getMD5() { return PSTR("d41d8cd98f00b204e9800998ecf8427e");}; 42 | #endif 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "control_msgs/SingleJointPositionGoal.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class SingleJointPositionActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef control_msgs::SingleJointPositionGoal _goal_type; 24 | _goal_type goal; 25 | 26 | SingleJointPositionActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/SingleJointPositionActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/SingleJointPositionActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("4b0d3d091471663e17749c1d0db90f61");}; 58 | #else 59 | const char * getMD5() { return PSTR("4b0d3d091471663e17749c1d0db90f61");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "control_msgs/SingleJointPositionResult.h" 12 | 13 | namespace control_msgs 14 | { 15 | 16 | class SingleJointPositionActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef control_msgs::SingleJointPositionResult _result_type; 24 | _result_type result; 25 | 26 | SingleJointPositionActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("control_msgs/SingleJointPositionActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("control_msgs/SingleJointPositionActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("1eb06eeff08fa7ea874431638cb52332");}; 58 | #else 59 | const char * getMD5() { return PSTR("1eb06eeff08fa7ea874431638cb52332");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class SingleJointPositionResult : public ros::Msg 14 | { 15 | public: 16 | 17 | SingleJointPositionResult() 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 | #ifdef ESP8266 34 | const char * getType() { return ("control_msgs/SingleJointPositionResult");}; 35 | #else 36 | const char * getType() { return PSTR("control_msgs/SingleJointPositionResult");}; 37 | #endif 38 | #ifdef ESP8266 39 | const char * getMD5() { return ("d41d8cd98f00b204e9800998ecf8427e");}; 40 | #else 41 | const char * getMD5() { return PSTR("d41d8cd98f00b204e9800998ecf8427e");}; 42 | #endif 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/dynamic_reconfigure/SensorLevels.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_SensorLevels_h 2 | #define _ROS_dynamic_reconfigure_SensorLevels_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | static const char dynamic_reconfigure_SensorLevels_type[] PROGMEM= "dynamic_reconfigure/SensorLevels"; 13 | static const char dynamic_reconfigure_SensorLevels_md5[] PROGMEM= "6322637bee96d5489db6e2127c47602c"; 14 | class SensorLevels : public ros::Msg 15 | { 16 | public: 17 | enum { RECONFIGURE_CLOSE = 3 }; 18 | enum { RECONFIGURE_STOP = 1 }; 19 | enum { RECONFIGURE_RUNNING = 0 }; 20 | 21 | SensorLevels() 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) override 32 | { 33 | int offset = 0; 34 | return offset; 35 | } 36 | 37 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)dynamic_reconfigure_SensorLevels_type);return type_msg; }; 38 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)dynamic_reconfigure_SensorLevels_md5);return md5_msg; }; 39 | 40 | }; 41 | 42 | } 43 | #endif 44 | -------------------------------------------------------------------------------- /src/geometry_msgs/Accel.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Accel_h 2 | #define _ROS_geometry_msgs_Accel_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_Accel_type[] PROGMEM= "geometry_msgs/Accel"; 14 | static const char geometry_msgs_Accel_md5[] PROGMEM= "9f195f881246fdfa2798d1d3eebca84a"; 15 | class Accel : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Vector3 _linear_type; 19 | _linear_type linear; 20 | typedef geometry_msgs::Vector3 _angular_type; 21 | _angular_type angular; 22 | 23 | Accel(): 24 | linear(), 25 | angular() 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += this->linear.serialize(outbuffer + offset); 33 | offset += this->angular.serialize(outbuffer + offset); 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) override 38 | { 39 | int offset = 0; 40 | offset += this->linear.deserialize(inbuffer + offset); 41 | offset += this->angular.deserialize(inbuffer + offset); 42 | return offset; 43 | } 44 | 45 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Accel_type);return type_msg; }; 46 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Accel_md5);return md5_msg; }; 47 | 48 | }; 49 | 50 | } 51 | #endif 52 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelStamped_h 2 | #define _ROS_geometry_msgs_AccelStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Accel.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_AccelStamped_type[] PROGMEM= "geometry_msgs/AccelStamped"; 15 | static const char geometry_msgs_AccelStamped_md5[] PROGMEM= "d8a98a5d81351b6eb0578c78557e7659"; 16 | class AccelStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Accel _accel_type; 22 | _accel_type accel; 23 | 24 | AccelStamped(): 25 | header(), 26 | accel() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->accel.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->accel.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_AccelStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_AccelStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovariance_h 2 | #define _ROS_geometry_msgs_AccelWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Accel.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_AccelWithCovariance_type[] PROGMEM= "geometry_msgs/AccelWithCovariance"; 14 | static const char geometry_msgs_AccelWithCovariance_md5[] PROGMEM= "ad5a718d699c6be72a02b8d6a139f334"; 15 | class AccelWithCovariance : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Accel _accel_type; 19 | _accel_type accel; 20 | float covariance[36]; 21 | 22 | AccelWithCovariance(): 23 | accel(), 24 | covariance() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->accel.serialize(outbuffer + offset); 32 | for( uint32_t i = 0; i < 36; i++){ 33 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 34 | } 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->accel.deserialize(inbuffer + offset); 42 | for( uint32_t i = 0; i < 36; i++){ 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 44 | } 45 | return offset; 46 | } 47 | 48 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_AccelWithCovariance_type);return type_msg; }; 49 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_AccelWithCovariance_md5);return md5_msg; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/geometry_msgs/AccelWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_AccelWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/AccelWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_AccelWithCovarianceStamped_type[] PROGMEM= "geometry_msgs/AccelWithCovarianceStamped"; 15 | static const char geometry_msgs_AccelWithCovarianceStamped_md5[] PROGMEM= "96adb295225031ec8d57fb4251b0a886"; 16 | class AccelWithCovarianceStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::AccelWithCovariance _accel_type; 22 | _accel_type accel; 23 | 24 | AccelWithCovarianceStamped(): 25 | header(), 26 | accel() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->accel.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->accel.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_AccelWithCovarianceStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_AccelWithCovarianceStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/InertiaStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_InertiaStamped_h 2 | #define _ROS_geometry_msgs_InertiaStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Inertia.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_InertiaStamped_type[] PROGMEM= "geometry_msgs/InertiaStamped"; 15 | static const char geometry_msgs_InertiaStamped_md5[] PROGMEM= "ddee48caeab5a966c5e8d166654a9ac7"; 16 | class InertiaStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Inertia _inertia_type; 22 | _inertia_type inertia; 23 | 24 | InertiaStamped(): 25 | header(), 26 | inertia() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->inertia.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->inertia.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_InertiaStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_InertiaStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Point.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Point_h 2 | #define _ROS_geometry_msgs_Point_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | static const char geometry_msgs_Point_type[] PROGMEM= "geometry_msgs/Point"; 13 | static const char geometry_msgs_Point_md5[] PROGMEM= "4a842b65f413084dc2b10fb484ea7f17"; 14 | class Point : public ros::Msg 15 | { 16 | public: 17 | typedef float _x_type; 18 | _x_type x; 19 | typedef float _y_type; 20 | _y_type y; 21 | typedef float _z_type; 22 | _z_type z; 23 | 24 | Point(): 25 | x(0), 26 | y(0), 27 | z(0) 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const override 32 | { 33 | int offset = 0; 34 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) override 41 | { 42 | int offset = 0; 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 46 | return offset; 47 | } 48 | 49 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Point_type);return type_msg; }; 50 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Point_md5);return md5_msg; }; 51 | 52 | }; 53 | 54 | } 55 | #endif 56 | -------------------------------------------------------------------------------- /src/geometry_msgs/PointStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PointStamped_h 2 | #define _ROS_geometry_msgs_PointStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Point.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_PointStamped_type[] PROGMEM= "geometry_msgs/PointStamped"; 15 | static const char geometry_msgs_PointStamped_md5[] PROGMEM= "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; 16 | class PointStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Point _point_type; 22 | _point_type point; 23 | 24 | PointStamped(): 25 | header(), 26 | point() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->point.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->point.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_PointStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_PointStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/PolygonStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PolygonStamped_h 2 | #define _ROS_geometry_msgs_PolygonStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Polygon.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_PolygonStamped_type[] PROGMEM= "geometry_msgs/PolygonStamped"; 15 | static const char geometry_msgs_PolygonStamped_md5[] PROGMEM= "c6be8f7dc3bee7fe9e8d296070f53340"; 16 | class PolygonStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Polygon _polygon_type; 22 | _polygon_type polygon; 23 | 24 | PolygonStamped(): 25 | header(), 26 | polygon() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->polygon.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->polygon.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_PolygonStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_PolygonStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Pose.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose_h 2 | #define _ROS_geometry_msgs_Pose_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Point.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_Pose_type[] PROGMEM= "geometry_msgs/Pose"; 15 | static const char geometry_msgs_Pose_md5[] PROGMEM= "e45d45a5a1ce597b249e23fb30fc871f"; 16 | class Pose : public ros::Msg 17 | { 18 | public: 19 | typedef geometry_msgs::Point _position_type; 20 | _position_type position; 21 | typedef geometry_msgs::Quaternion _orientation_type; 22 | _orientation_type orientation; 23 | 24 | Pose(): 25 | position(), 26 | orientation() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->position.serialize(outbuffer + offset); 34 | offset += this->orientation.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->position.deserialize(inbuffer + offset); 42 | offset += this->orientation.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Pose_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Pose_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Pose2D.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose2D_h 2 | #define _ROS_geometry_msgs_Pose2D_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | static const char geometry_msgs_Pose2D_type[] PROGMEM= "geometry_msgs/Pose2D"; 13 | static const char geometry_msgs_Pose2D_md5[] PROGMEM= "938fa65709584ad8e77d238529be13b8"; 14 | class Pose2D : public ros::Msg 15 | { 16 | public: 17 | typedef float _x_type; 18 | _x_type x; 19 | typedef float _y_type; 20 | _y_type y; 21 | typedef float _theta_type; 22 | _theta_type theta; 23 | 24 | Pose2D(): 25 | x(0), 26 | y(0), 27 | theta(0) 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const override 32 | { 33 | int offset = 0; 34 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->theta); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) override 41 | { 42 | int offset = 0; 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->theta)); 46 | return offset; 47 | } 48 | 49 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Pose2D_type);return type_msg; }; 50 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Pose2D_md5);return md5_msg; }; 51 | 52 | }; 53 | 54 | } 55 | #endif 56 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseStamped_h 2 | #define _ROS_geometry_msgs_PoseStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Pose.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_PoseStamped_type[] PROGMEM= "geometry_msgs/PoseStamped"; 15 | static const char geometry_msgs_PoseStamped_md5[] PROGMEM= "d3812c3cbc69362b77dc0b19b345f8f5"; 16 | class PoseStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Pose _pose_type; 22 | _pose_type pose; 23 | 24 | PoseStamped(): 25 | header(), 26 | pose() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->pose.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->pose.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_PoseStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_PoseStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovariance_h 2 | #define _ROS_geometry_msgs_PoseWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Pose.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_PoseWithCovariance_type[] PROGMEM= "geometry_msgs/PoseWithCovariance"; 14 | static const char geometry_msgs_PoseWithCovariance_md5[] PROGMEM= "c23e848cf1b7533a8d7c259073a97e6f"; 15 | class PoseWithCovariance : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Pose _pose_type; 19 | _pose_type pose; 20 | float covariance[36]; 21 | 22 | PoseWithCovariance(): 23 | pose(), 24 | covariance() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->pose.serialize(outbuffer + offset); 32 | for( uint32_t i = 0; i < 36; i++){ 33 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 34 | } 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->pose.deserialize(inbuffer + offset); 42 | for( uint32_t i = 0; i < 36; i++){ 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 44 | } 45 | return offset; 46 | } 47 | 48 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_PoseWithCovariance_type);return type_msg; }; 49 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_PoseWithCovariance_md5);return md5_msg; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/geometry_msgs/PoseWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_PoseWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/PoseWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_PoseWithCovarianceStamped_type[] PROGMEM= "geometry_msgs/PoseWithCovarianceStamped"; 15 | static const char geometry_msgs_PoseWithCovarianceStamped_md5[] PROGMEM= "953b798c0f514ff060a53a3498ce6246"; 16 | class PoseWithCovarianceStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::PoseWithCovariance _pose_type; 22 | _pose_type pose; 23 | 24 | PoseWithCovarianceStamped(): 25 | header(), 26 | pose() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->pose.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->pose.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_PoseWithCovarianceStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_PoseWithCovarianceStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Quaternion.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Quaternion_h 2 | #define _ROS_geometry_msgs_Quaternion_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | static const char geometry_msgs_Quaternion_type[] PROGMEM= "geometry_msgs/Quaternion"; 13 | static const char geometry_msgs_Quaternion_md5[] PROGMEM= "a779879fadf0160734f906b8c19c7004"; 14 | class Quaternion : public ros::Msg 15 | { 16 | public: 17 | typedef float _x_type; 18 | _x_type x; 19 | typedef float _y_type; 20 | _y_type y; 21 | typedef float _z_type; 22 | _z_type z; 23 | typedef float _w_type; 24 | _w_type w; 25 | 26 | Quaternion(): 27 | x(0), 28 | y(0), 29 | z(0), 30 | w(0) 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 38 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 39 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 40 | offset += serializeAvrFloat64(outbuffer + offset, this->w); 41 | return offset; 42 | } 43 | 44 | virtual int deserialize(unsigned char *inbuffer) override 45 | { 46 | int offset = 0; 47 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 48 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 49 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 50 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->w)); 51 | return offset; 52 | } 53 | 54 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Quaternion_type);return type_msg; }; 55 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Quaternion_md5);return md5_msg; }; 56 | 57 | }; 58 | 59 | } 60 | #endif 61 | -------------------------------------------------------------------------------- /src/geometry_msgs/QuaternionStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_QuaternionStamped_h 2 | #define _ROS_geometry_msgs_QuaternionStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_QuaternionStamped_type[] PROGMEM= "geometry_msgs/QuaternionStamped"; 15 | static const char geometry_msgs_QuaternionStamped_md5[] PROGMEM= "e57f1e547e0e1fd13504588ffc8334e2"; 16 | class QuaternionStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Quaternion _quaternion_type; 22 | _quaternion_type quaternion; 23 | 24 | QuaternionStamped(): 25 | header(), 26 | quaternion() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->quaternion.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->quaternion.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_QuaternionStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_QuaternionStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Transform.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Transform_h 2 | #define _ROS_geometry_msgs_Transform_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_Transform_type[] PROGMEM= "geometry_msgs/Transform"; 15 | static const char geometry_msgs_Transform_md5[] PROGMEM= "ac9eff44abf714214112b05d54a3cf9b"; 16 | class Transform : public ros::Msg 17 | { 18 | public: 19 | typedef geometry_msgs::Vector3 _translation_type; 20 | _translation_type translation; 21 | typedef geometry_msgs::Quaternion _rotation_type; 22 | _rotation_type rotation; 23 | 24 | Transform(): 25 | translation(), 26 | rotation() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->translation.serialize(outbuffer + offset); 34 | offset += this->rotation.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->translation.deserialize(inbuffer + offset); 42 | offset += this->rotation.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Transform_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Transform_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Twist.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Twist_h 2 | #define _ROS_geometry_msgs_Twist_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_Twist_type[] PROGMEM= "geometry_msgs/Twist"; 14 | static const char geometry_msgs_Twist_md5[] PROGMEM= "9f195f881246fdfa2798d1d3eebca84a"; 15 | class Twist : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Vector3 _linear_type; 19 | _linear_type linear; 20 | typedef geometry_msgs::Vector3 _angular_type; 21 | _angular_type angular; 22 | 23 | Twist(): 24 | linear(), 25 | angular() 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += this->linear.serialize(outbuffer + offset); 33 | offset += this->angular.serialize(outbuffer + offset); 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) override 38 | { 39 | int offset = 0; 40 | offset += this->linear.deserialize(inbuffer + offset); 41 | offset += this->angular.deserialize(inbuffer + offset); 42 | return offset; 43 | } 44 | 45 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Twist_type);return type_msg; }; 46 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Twist_md5);return md5_msg; }; 47 | 48 | }; 49 | 50 | } 51 | #endif 52 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistStamped_h 2 | #define _ROS_geometry_msgs_TwistStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Twist.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_TwistStamped_type[] PROGMEM= "geometry_msgs/TwistStamped"; 15 | static const char geometry_msgs_TwistStamped_md5[] PROGMEM= "98d34b0043a2093cf9d9345ab6eef12e"; 16 | class TwistStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Twist _twist_type; 22 | _twist_type twist; 23 | 24 | TwistStamped(): 25 | header(), 26 | twist() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->twist.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->twist.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_TwistStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_TwistStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovariance_h 2 | #define _ROS_geometry_msgs_TwistWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Twist.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_TwistWithCovariance_type[] PROGMEM= "geometry_msgs/TwistWithCovariance"; 14 | static const char geometry_msgs_TwistWithCovariance_md5[] PROGMEM= "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; 15 | class TwistWithCovariance : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Twist _twist_type; 19 | _twist_type twist; 20 | float covariance[36]; 21 | 22 | TwistWithCovariance(): 23 | twist(), 24 | covariance() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const override 29 | { 30 | int offset = 0; 31 | offset += this->twist.serialize(outbuffer + offset); 32 | for( uint32_t i = 0; i < 36; i++){ 33 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 34 | } 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->twist.deserialize(inbuffer + offset); 42 | for( uint32_t i = 0; i < 36; i++){ 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 44 | } 45 | return offset; 46 | } 47 | 48 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_TwistWithCovariance_type);return type_msg; }; 49 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_TwistWithCovariance_md5);return md5_msg; }; 50 | 51 | }; 52 | 53 | } 54 | #endif 55 | -------------------------------------------------------------------------------- /src/geometry_msgs/TwistWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_TwistWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/TwistWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_TwistWithCovarianceStamped_type[] PROGMEM= "geometry_msgs/TwistWithCovarianceStamped"; 15 | static const char geometry_msgs_TwistWithCovarianceStamped_md5[] PROGMEM= "8927a1a12fb2607ceea095b2dc440a96"; 16 | class TwistWithCovarianceStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::TwistWithCovariance _twist_type; 22 | _twist_type twist; 23 | 24 | TwistWithCovarianceStamped(): 25 | header(), 26 | twist() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->twist.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->twist.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_TwistWithCovarianceStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_TwistWithCovarianceStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3_h 2 | #define _ROS_geometry_msgs_Vector3_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | static const char geometry_msgs_Vector3_type[] PROGMEM= "geometry_msgs/Vector3"; 13 | static const char geometry_msgs_Vector3_md5[] PROGMEM= "4a842b65f413084dc2b10fb484ea7f17"; 14 | class Vector3 : public ros::Msg 15 | { 16 | public: 17 | typedef float _x_type; 18 | _x_type x; 19 | typedef float _y_type; 20 | _y_type y; 21 | typedef float _z_type; 22 | _z_type z; 23 | 24 | Vector3(): 25 | x(0), 26 | y(0), 27 | z(0) 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const override 32 | { 33 | int offset = 0; 34 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) override 41 | { 42 | int offset = 0; 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 46 | return offset; 47 | } 48 | 49 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Vector3_type);return type_msg; }; 50 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Vector3_md5);return md5_msg; }; 51 | 52 | }; 53 | 54 | } 55 | #endif 56 | -------------------------------------------------------------------------------- /src/geometry_msgs/Vector3Stamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3Stamped_h 2 | #define _ROS_geometry_msgs_Vector3Stamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Vector3.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_Vector3Stamped_type[] PROGMEM= "geometry_msgs/Vector3Stamped"; 15 | static const char geometry_msgs_Vector3Stamped_md5[] PROGMEM= "7b324c7325e683bf02a9b14b01090ec7"; 16 | class Vector3Stamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Vector3 _vector_type; 22 | _vector_type vector; 23 | 24 | Vector3Stamped(): 25 | header(), 26 | vector() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->vector.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->vector.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Vector3Stamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Vector3Stamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/geometry_msgs/Wrench.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Wrench_h 2 | #define _ROS_geometry_msgs_Wrench_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | static const char geometry_msgs_Wrench_type[] PROGMEM= "geometry_msgs/Wrench"; 14 | static const char geometry_msgs_Wrench_md5[] PROGMEM= "4f539cf138b23283b520fd271b567936"; 15 | class Wrench : public ros::Msg 16 | { 17 | public: 18 | typedef geometry_msgs::Vector3 _force_type; 19 | _force_type force; 20 | typedef geometry_msgs::Vector3 _torque_type; 21 | _torque_type torque; 22 | 23 | Wrench(): 24 | force(), 25 | torque() 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const override 30 | { 31 | int offset = 0; 32 | offset += this->force.serialize(outbuffer + offset); 33 | offset += this->torque.serialize(outbuffer + offset); 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) override 38 | { 39 | int offset = 0; 40 | offset += this->force.deserialize(inbuffer + offset); 41 | offset += this->torque.deserialize(inbuffer + offset); 42 | return offset; 43 | } 44 | 45 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_Wrench_type);return type_msg; }; 46 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_Wrench_md5);return md5_msg; }; 47 | 48 | }; 49 | 50 | } 51 | #endif 52 | -------------------------------------------------------------------------------- /src/geometry_msgs/WrenchStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_WrenchStamped_h 2 | #define _ROS_geometry_msgs_WrenchStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Wrench.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | static const char geometry_msgs_WrenchStamped_type[] PROGMEM= "geometry_msgs/WrenchStamped"; 15 | static const char geometry_msgs_WrenchStamped_md5[] PROGMEM= "d78d3cb249ce23087ade7e7d0c40cfa7"; 16 | class WrenchStamped : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef geometry_msgs::Wrench _wrench_type; 22 | _wrench_type wrench; 23 | 24 | WrenchStamped(): 25 | header(), 26 | wrench() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->header.serialize(outbuffer + offset); 34 | offset += this->wrench.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->header.deserialize(inbuffer + offset); 42 | offset += this->wrench.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)geometry_msgs_WrenchStamped_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)geometry_msgs_WrenchStamped_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "nav_msgs/OccupancyGrid.h" 10 | 11 | namespace map_msgs 12 | { 13 | 14 | class ProjectedMap : public ros::Msg 15 | { 16 | public: 17 | typedef nav_msgs::OccupancyGrid _map_type; 18 | _map_type map; 19 | typedef float _min_z_type; 20 | _min_z_type min_z; 21 | typedef float _max_z_type; 22 | _max_z_type max_z; 23 | 24 | ProjectedMap(): 25 | map(), 26 | min_z(0), 27 | max_z(0) 28 | { 29 | } 30 | 31 | virtual int serialize(unsigned char *outbuffer) const 32 | { 33 | int offset = 0; 34 | offset += this->map.serialize(outbuffer + offset); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->min_z); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->max_z); 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) 41 | { 42 | int offset = 0; 43 | offset += this->map.deserialize(inbuffer + offset); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_z)); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_z)); 46 | return offset; 47 | } 48 | 49 | #ifdef ESP8266 50 | const char * getType() { return ("map_msgs/ProjectedMap");}; 51 | #else 52 | const char * getType() { return PSTR("map_msgs/ProjectedMap");}; 53 | #endif 54 | #ifdef ESP8266 55 | const char * getMD5() { return ("7bbe8f96e45089681dc1ea7d023cbfca");}; 56 | #else 57 | const char * getMD5() { return PSTR("7bbe8f96e45089681dc1ea7d023cbfca");}; 58 | #endif 59 | 60 | }; 61 | 62 | } 63 | #endif 64 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapAction.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapAction_h 2 | #define _ROS_nav_msgs_GetMapAction_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/GetMapActionGoal.h" 9 | #include "nav_msgs/GetMapActionResult.h" 10 | #include "nav_msgs/GetMapActionFeedback.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | static const char nav_msgs_GetMapAction_type[] PROGMEM= "nav_msgs/GetMapAction"; 16 | static const char nav_msgs_GetMapAction_md5[] PROGMEM= "e611ad23fbf237c031b7536416dc7cd7"; 17 | class GetMapAction : public ros::Msg 18 | { 19 | public: 20 | typedef nav_msgs::GetMapActionGoal _action_goal_type; 21 | _action_goal_type action_goal; 22 | typedef nav_msgs::GetMapActionResult _action_result_type; 23 | _action_result_type action_result; 24 | typedef nav_msgs::GetMapActionFeedback _action_feedback_type; 25 | _action_feedback_type action_feedback; 26 | 27 | GetMapAction(): 28 | action_goal(), 29 | action_result(), 30 | action_feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->action_goal.serialize(outbuffer + offset); 38 | offset += this->action_result.serialize(outbuffer + offset); 39 | offset += this->action_feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->action_goal.deserialize(inbuffer + offset); 47 | offset += this->action_result.deserialize(inbuffer + offset); 48 | offset += this->action_feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapAction_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapAction_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionFeedback_h 2 | #define _ROS_nav_msgs_GetMapActionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "nav_msgs/GetMapFeedback.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | static const char nav_msgs_GetMapActionFeedback_type[] PROGMEM= "nav_msgs/GetMapActionFeedback"; 16 | static const char nav_msgs_GetMapActionFeedback_md5[] PROGMEM= "aae20e09065c3809e8a8e87c4c8953fd"; 17 | class GetMapActionFeedback : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef nav_msgs::GetMapFeedback _feedback_type; 25 | _feedback_type feedback; 26 | 27 | GetMapActionFeedback(): 28 | header(), 29 | status(), 30 | feedback() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->feedback.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->feedback.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapActionFeedback_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapActionFeedback_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionGoal_h 2 | #define _ROS_nav_msgs_GetMapActionGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalID.h" 10 | #include "nav_msgs/GetMapGoal.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | static const char nav_msgs_GetMapActionGoal_type[] PROGMEM= "nav_msgs/GetMapActionGoal"; 16 | static const char nav_msgs_GetMapActionGoal_md5[] PROGMEM= "4b30be6cd12b9e72826df56b481f40e0"; 17 | class GetMapActionGoal : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalID _goal_id_type; 23 | _goal_id_type goal_id; 24 | typedef nav_msgs::GetMapGoal _goal_type; 25 | _goal_type goal; 26 | 27 | GetMapActionGoal(): 28 | header(), 29 | goal_id(), 30 | goal() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->goal_id.serialize(outbuffer + offset); 39 | offset += this->goal.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->goal_id.deserialize(inbuffer + offset); 48 | offset += this->goal.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapActionGoal_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapActionGoal_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapActionResult_h 2 | #define _ROS_nav_msgs_GetMapActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "nav_msgs/GetMapResult.h" 11 | 12 | namespace nav_msgs 13 | { 14 | 15 | static const char nav_msgs_GetMapActionResult_type[] PROGMEM= "nav_msgs/GetMapActionResult"; 16 | static const char nav_msgs_GetMapActionResult_md5[] PROGMEM= "ac66e5b9a79bb4bbd33dab245236c892"; 17 | class GetMapActionResult : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef nav_msgs::GetMapResult _result_type; 25 | _result_type result; 26 | 27 | GetMapActionResult(): 28 | header(), 29 | status(), 30 | result() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->result.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->result.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapActionResult_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapActionResult_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapFeedback_h 2 | #define _ROS_nav_msgs_GetMapFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | static const char nav_msgs_GetMapFeedback_type[] PROGMEM= "nav_msgs/GetMapFeedback"; 13 | static const char nav_msgs_GetMapFeedback_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class GetMapFeedback : public ros::Msg 15 | { 16 | public: 17 | 18 | GetMapFeedback() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapFeedback_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapFeedback_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapGoal_h 2 | #define _ROS_nav_msgs_GetMapGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | static const char nav_msgs_GetMapGoal_type[] PROGMEM= "nav_msgs/GetMapGoal"; 13 | static const char nav_msgs_GetMapGoal_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class GetMapGoal : public ros::Msg 15 | { 16 | public: 17 | 18 | GetMapGoal() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapGoal_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapGoal_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/nav_msgs/GetMapResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapResult_h 2 | #define _ROS_nav_msgs_GetMapResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/OccupancyGrid.h" 9 | 10 | namespace nav_msgs 11 | { 12 | 13 | static const char nav_msgs_GetMapResult_type[] PROGMEM= "nav_msgs/GetMapResult"; 14 | static const char nav_msgs_GetMapResult_md5[] PROGMEM= "6cdd0a18e0aff5b0a3ca2326a89b54ff"; 15 | class GetMapResult : public ros::Msg 16 | { 17 | public: 18 | typedef nav_msgs::OccupancyGrid _map_type; 19 | _map_type map; 20 | 21 | GetMapResult(): 22 | map() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const override 27 | { 28 | int offset = 0; 29 | offset += this->map.serialize(outbuffer + offset); 30 | return offset; 31 | } 32 | 33 | virtual int deserialize(unsigned char *inbuffer) override 34 | { 35 | int offset = 0; 36 | offset += this->map.deserialize(inbuffer + offset); 37 | return offset; 38 | } 39 | 40 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)nav_msgs_GetMapResult_type);return type_msg; }; 41 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)nav_msgs_GetMapResult_md5);return md5_msg; }; 42 | 43 | }; 44 | 45 | } 46 | #endif 47 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | 11 | namespace rospy_tutorials 12 | { 13 | 14 | class HeaderString : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef const char* _data_type; 20 | _data_type data; 21 | 22 | HeaderString(): 23 | header(), 24 | data("") 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | uint32_t length_data = strlen(this->data); 33 | varToArr(outbuffer + offset, length_data); 34 | offset += 4; 35 | memcpy(outbuffer + offset, this->data, length_data); 36 | offset += length_data; 37 | return offset; 38 | } 39 | 40 | virtual int deserialize(unsigned char *inbuffer) 41 | { 42 | int offset = 0; 43 | offset += this->header.deserialize(inbuffer + offset); 44 | uint32_t length_data; 45 | arrToVar(length_data, (inbuffer + offset)); 46 | offset += 4; 47 | for(unsigned int k= offset; k< offset+length_data; ++k){ 48 | inbuffer[k-1]=inbuffer[k]; 49 | } 50 | inbuffer[offset+length_data-1]=0; 51 | this->data = (char *)(inbuffer + offset-1); 52 | offset += length_data; 53 | return offset; 54 | } 55 | 56 | #ifdef ESP8266 57 | const char * getType() { return ("rospy_tutorials/HeaderString");}; 58 | #else 59 | const char * getType() { return PSTR("rospy_tutorials/HeaderString");}; 60 | #endif 61 | #ifdef ESP8266 62 | const char * getMD5() { return ("c99a9440709e4d4a9716d55b8270d5e7");}; 63 | #else 64 | const char * getMD5() { return PSTR("c99a9440709e4d4a9716d55b8270d5e7");}; 65 | #endif 66 | 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /src/sensor_msgs/FluidPressure.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_FluidPressure_h 2 | #define _ROS_sensor_msgs_FluidPressure_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | static const char sensor_msgs_FluidPressure_type[] PROGMEM= "sensor_msgs/FluidPressure"; 14 | static const char sensor_msgs_FluidPressure_md5[] PROGMEM= "804dc5cea1c5306d6a2eb80b9833befe"; 15 | class FluidPressure : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef float _fluid_pressure_type; 21 | _fluid_pressure_type fluid_pressure; 22 | typedef float _variance_type; 23 | _variance_type variance; 24 | 25 | FluidPressure(): 26 | header(), 27 | fluid_pressure(0), 28 | variance(0) 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->fluid_pressure); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->fluid_pressure)); 46 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)sensor_msgs_FluidPressure_type);return type_msg; }; 51 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)sensor_msgs_FluidPressure_md5);return md5_msg; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/sensor_msgs/Illuminance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_Illuminance_h 2 | #define _ROS_sensor_msgs_Illuminance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | static const char sensor_msgs_Illuminance_type[] PROGMEM= "sensor_msgs/Illuminance"; 14 | static const char sensor_msgs_Illuminance_md5[] PROGMEM= "8cf5febb0952fca9d650c3d11a81a188"; 15 | class Illuminance : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef float _illuminance_type; 21 | _illuminance_type illuminance; 22 | typedef float _variance_type; 23 | _variance_type variance; 24 | 25 | Illuminance(): 26 | header(), 27 | illuminance(0), 28 | variance(0) 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->illuminance); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->illuminance)); 46 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)sensor_msgs_Illuminance_type);return type_msg; }; 51 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)sensor_msgs_Illuminance_md5);return md5_msg; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/sensor_msgs/RelativeHumidity.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_RelativeHumidity_h 2 | #define _ROS_sensor_msgs_RelativeHumidity_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | static const char sensor_msgs_RelativeHumidity_type[] PROGMEM= "sensor_msgs/RelativeHumidity"; 14 | static const char sensor_msgs_RelativeHumidity_md5[] PROGMEM= "8730015b05955b7e992ce29a2678d90f"; 15 | class RelativeHumidity : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef float _relative_humidity_type; 21 | _relative_humidity_type relative_humidity; 22 | typedef float _variance_type; 23 | _variance_type variance; 24 | 25 | RelativeHumidity(): 26 | header(), 27 | relative_humidity(0), 28 | variance(0) 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->relative_humidity); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->relative_humidity)); 46 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)sensor_msgs_RelativeHumidity_type);return type_msg; }; 51 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)sensor_msgs_RelativeHumidity_md5);return md5_msg; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/sensor_msgs/Temperature.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sensor_msgs_Temperature_h 2 | #define _ROS_sensor_msgs_Temperature_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | 10 | namespace sensor_msgs 11 | { 12 | 13 | static const char sensor_msgs_Temperature_type[] PROGMEM= "sensor_msgs/Temperature"; 14 | static const char sensor_msgs_Temperature_md5[] PROGMEM= "ff71b307acdbe7c871a5a6d7ed359100"; 15 | class Temperature : public ros::Msg 16 | { 17 | public: 18 | typedef std_msgs::Header _header_type; 19 | _header_type header; 20 | typedef float _temperature_type; 21 | _temperature_type temperature; 22 | typedef float _variance_type; 23 | _variance_type variance; 24 | 25 | Temperature(): 26 | header(), 27 | temperature(0), 28 | variance(0) 29 | { 30 | } 31 | 32 | virtual int serialize(unsigned char *outbuffer) const override 33 | { 34 | int offset = 0; 35 | offset += this->header.serialize(outbuffer + offset); 36 | offset += serializeAvrFloat64(outbuffer + offset, this->temperature); 37 | offset += serializeAvrFloat64(outbuffer + offset, this->variance); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | offset += this->header.deserialize(inbuffer + offset); 45 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->temperature)); 46 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->variance)); 47 | return offset; 48 | } 49 | 50 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)sensor_msgs_Temperature_type);return type_msg; }; 51 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)sensor_msgs_Temperature_md5);return md5_msg; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/shape_msgs/MeshTriangle.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_shape_msgs_MeshTriangle_h 2 | #define _ROS_shape_msgs_MeshTriangle_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace shape_msgs 10 | { 11 | 12 | static const char shape_msgs_MeshTriangle_type[] PROGMEM= "shape_msgs/MeshTriangle"; 13 | static const char shape_msgs_MeshTriangle_md5[] PROGMEM= "23688b2e6d2de3d32fe8af104a903253"; 14 | class MeshTriangle : public ros::Msg 15 | { 16 | public: 17 | uint32_t vertex_indices[3]; 18 | 19 | MeshTriangle(): 20 | vertex_indices() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | for( uint32_t i = 0; i < 3; i++){ 28 | *(outbuffer + offset + 0) = (this->vertex_indices[i] >> (8 * 0)) & 0xFF; 29 | *(outbuffer + offset + 1) = (this->vertex_indices[i] >> (8 * 1)) & 0xFF; 30 | *(outbuffer + offset + 2) = (this->vertex_indices[i] >> (8 * 2)) & 0xFF; 31 | *(outbuffer + offset + 3) = (this->vertex_indices[i] >> (8 * 3)) & 0xFF; 32 | offset += sizeof(this->vertex_indices[i]); 33 | } 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) override 38 | { 39 | int offset = 0; 40 | for( uint32_t i = 0; i < 3; i++){ 41 | this->vertex_indices[i] = ((uint32_t) (*(inbuffer + offset))); 42 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 43 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 44 | this->vertex_indices[i] |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 45 | offset += sizeof(this->vertex_indices[i]); 46 | } 47 | return offset; 48 | } 49 | 50 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)shape_msgs_MeshTriangle_type);return type_msg; }; 51 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)shape_msgs_MeshTriangle_md5);return md5_msg; }; 52 | 53 | }; 54 | 55 | } 56 | #endif 57 | -------------------------------------------------------------------------------- /src/shape_msgs/Plane.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_shape_msgs_Plane_h 2 | #define _ROS_shape_msgs_Plane_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace shape_msgs 10 | { 11 | 12 | static const char shape_msgs_Plane_type[] PROGMEM= "shape_msgs/Plane"; 13 | static const char shape_msgs_Plane_md5[] PROGMEM= "2c1b92ed8f31492f8e73f6a4a44ca796"; 14 | class Plane : public ros::Msg 15 | { 16 | public: 17 | float coef[4]; 18 | 19 | Plane(): 20 | coef() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const override 25 | { 26 | int offset = 0; 27 | for( uint32_t i = 0; i < 4; i++){ 28 | offset += serializeAvrFloat64(outbuffer + offset, this->coef[i]); 29 | } 30 | return offset; 31 | } 32 | 33 | virtual int deserialize(unsigned char *inbuffer) override 34 | { 35 | int offset = 0; 36 | for( uint32_t i = 0; i < 4; i++){ 37 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->coef[i])); 38 | } 39 | return offset; 40 | } 41 | 42 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)shape_msgs_Plane_type);return type_msg; }; 43 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)shape_msgs_Plane_md5);return md5_msg; }; 44 | 45 | }; 46 | 47 | } 48 | #endif 49 | -------------------------------------------------------------------------------- /src/std_msgs/Bool.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Bool_h 2 | #define _ROS_std_msgs_Bool_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Bool_type[] PROGMEM= "std_msgs/Bool"; 13 | static const char std_msgs_Bool_md5[] PROGMEM= "8b94c1b53db61fb6aed406028ad6332a"; 14 | class Bool : public ros::Msg 15 | { 16 | public: 17 | typedef bool _data_type; 18 | _data_type data; 19 | 20 | Bool(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | bool real; 30 | uint8_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | offset += sizeof(this->data); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | union { 42 | bool real; 43 | uint8_t base; 44 | } u_data; 45 | u_data.base = 0; 46 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 47 | this->data = u_data.real; 48 | offset += sizeof(this->data); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Bool_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Bool_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/std_msgs/Byte.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Byte_h 2 | #define _ROS_std_msgs_Byte_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Byte_type[] PROGMEM= "std_msgs/Byte"; 13 | static const char std_msgs_Byte_md5[] PROGMEM= "ad736a2e8818154c487bb80fe42ce43b"; 14 | class Byte : public ros::Msg 15 | { 16 | public: 17 | typedef int8_t _data_type; 18 | _data_type data; 19 | 20 | Byte(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | int8_t real; 30 | uint8_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | offset += sizeof(this->data); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | union { 42 | int8_t real; 43 | uint8_t base; 44 | } u_data; 45 | u_data.base = 0; 46 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 47 | this->data = u_data.real; 48 | offset += sizeof(this->data); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Byte_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Byte_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/std_msgs/Char.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Char_h 2 | #define _ROS_std_msgs_Char_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Char_type[] PROGMEM= "std_msgs/Char"; 13 | static const char std_msgs_Char_md5[] PROGMEM= "1bf77f25acecdedba0e224b162199717"; 14 | class Char : public ros::Msg 15 | { 16 | public: 17 | typedef uint8_t _data_type; 18 | _data_type data; 19 | 20 | Char(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 29 | offset += sizeof(this->data); 30 | return offset; 31 | } 32 | 33 | virtual int deserialize(unsigned char *inbuffer) override 34 | { 35 | int offset = 0; 36 | this->data = ((uint8_t) (*(inbuffer + offset))); 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Char_type);return type_msg; }; 42 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Char_md5);return md5_msg; }; 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/std_msgs/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Empty_h 2 | #define _ROS_std_msgs_Empty_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Empty_type[] PROGMEM= "std_msgs/Empty"; 13 | static const char std_msgs_Empty_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class Empty : public ros::Msg 15 | { 16 | public: 17 | 18 | Empty() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Empty_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Empty_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/std_msgs/Float32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Float32_h 2 | #define _ROS_std_msgs_Float32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Float32_type[] PROGMEM= "std_msgs/Float32"; 13 | static const char std_msgs_Float32_md5[] PROGMEM= "73fcbf46b49191e672908e50842a83d4"; 14 | class Float32 : public ros::Msg 15 | { 16 | public: 17 | typedef float _data_type; 18 | _data_type data; 19 | 20 | Float32(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | float real; 30 | uint32_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 35 | *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; 36 | *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | union { 45 | float real; 46 | uint32_t base; 47 | } u_data; 48 | u_data.base = 0; 49 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 50 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 51 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 52 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 53 | this->data = u_data.real; 54 | offset += sizeof(this->data); 55 | return offset; 56 | } 57 | 58 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Float32_type);return type_msg; }; 59 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Float32_md5);return md5_msg; }; 60 | 61 | }; 62 | 63 | } 64 | #endif 65 | -------------------------------------------------------------------------------- /src/std_msgs/Float64.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Float64_h 2 | #define _ROS_std_msgs_Float64_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Float64_type[] PROGMEM= "std_msgs/Float64"; 13 | static const char std_msgs_Float64_md5[] PROGMEM= "fdb28210bfa9d7c91146260178d9a584"; 14 | class Float64 : public ros::Msg 15 | { 16 | public: 17 | typedef float _data_type; 18 | _data_type data; 19 | 20 | Float64(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | offset += serializeAvrFloat64(outbuffer + offset, this->data); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) override 33 | { 34 | int offset = 0; 35 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->data)); 36 | return offset; 37 | } 38 | 39 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Float64_type);return type_msg; }; 40 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Float64_md5);return md5_msg; }; 41 | 42 | }; 43 | 44 | } 45 | #endif 46 | -------------------------------------------------------------------------------- /src/std_msgs/Int16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int16_h 2 | #define _ROS_std_msgs_Int16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Int16_type[] PROGMEM= "std_msgs/Int16"; 13 | static const char std_msgs_Int16_md5[] PROGMEM= "8524586e34fbd7cb1c08c5f5f1ca0e57"; 14 | class Int16 : public ros::Msg 15 | { 16 | public: 17 | typedef int16_t _data_type; 18 | _data_type data; 19 | 20 | Int16(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | int16_t real; 30 | uint16_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) override 40 | { 41 | int offset = 0; 42 | union { 43 | int16_t real; 44 | uint16_t base; 45 | } u_data; 46 | u_data.base = 0; 47 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); 48 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 49 | this->data = u_data.real; 50 | offset += sizeof(this->data); 51 | return offset; 52 | } 53 | 54 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Int16_type);return type_msg; }; 55 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Int16_md5);return md5_msg; }; 56 | 57 | }; 58 | 59 | } 60 | #endif 61 | -------------------------------------------------------------------------------- /src/std_msgs/Int32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int32_h 2 | #define _ROS_std_msgs_Int32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Int32_type[] PROGMEM= "std_msgs/Int32"; 13 | static const char std_msgs_Int32_md5[] PROGMEM= "da5909fbe378aeaf85e547e830cc1bb7"; 14 | class Int32 : public ros::Msg 15 | { 16 | public: 17 | typedef int32_t _data_type; 18 | _data_type data; 19 | 20 | Int32(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | int32_t real; 30 | uint32_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 35 | *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; 36 | *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | virtual int deserialize(unsigned char *inbuffer) override 42 | { 43 | int offset = 0; 44 | union { 45 | int32_t real; 46 | uint32_t base; 47 | } u_data; 48 | u_data.base = 0; 49 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 50 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 51 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 52 | u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 53 | this->data = u_data.real; 54 | offset += sizeof(this->data); 55 | return offset; 56 | } 57 | 58 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Int32_type);return type_msg; }; 59 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Int32_md5);return md5_msg; }; 60 | 61 | }; 62 | 63 | } 64 | #endif 65 | -------------------------------------------------------------------------------- /src/std_msgs/Int8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int8_h 2 | #define _ROS_std_msgs_Int8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_Int8_type[] PROGMEM= "std_msgs/Int8"; 13 | static const char std_msgs_Int8_md5[] PROGMEM= "27ffa0c9c4b8fb8492252bcad9e5c57b"; 14 | class Int8 : public ros::Msg 15 | { 16 | public: 17 | typedef int8_t _data_type; 18 | _data_type data; 19 | 20 | Int8(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | union { 29 | int8_t real; 30 | uint8_t base; 31 | } u_data; 32 | u_data.real = this->data; 33 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 34 | offset += sizeof(this->data); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | union { 42 | int8_t real; 43 | uint8_t base; 44 | } u_data; 45 | u_data.base = 0; 46 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 47 | this->data = u_data.real; 48 | offset += sizeof(this->data); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_Int8_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_Int8_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/std_msgs/String.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_String_h 2 | #define _ROS_std_msgs_String_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_String_type[] PROGMEM= "std_msgs/String"; 13 | static const char std_msgs_String_md5[] PROGMEM= "992ce8a1687cec8c8bd883ec73ca41d1"; 14 | class String : public ros::Msg 15 | { 16 | public: 17 | typedef const char* _data_type; 18 | _data_type data; 19 | 20 | String(): 21 | data("") 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | uint32_t length_data = strlen(this->data); 29 | varToArr(outbuffer + offset, length_data); 30 | offset += 4; 31 | memcpy(outbuffer + offset, this->data, length_data); 32 | offset += length_data; 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | uint32_t length_data; 40 | arrToVar(length_data, (inbuffer + offset)); 41 | offset += 4; 42 | for(unsigned int k= offset; k< offset+length_data; ++k){ 43 | inbuffer[k-1]=inbuffer[k]; 44 | } 45 | inbuffer[offset+length_data-1]=0; 46 | this->data = (char *)(inbuffer + offset-1); 47 | offset += length_data; 48 | return offset; 49 | } 50 | 51 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_String_type);return type_msg; }; 52 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_String_md5);return md5_msg; }; 53 | 54 | }; 55 | 56 | } 57 | #endif 58 | -------------------------------------------------------------------------------- /src/std_msgs/UInt16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt16_h 2 | #define _ROS_std_msgs_UInt16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_UInt16_type[] PROGMEM= "std_msgs/UInt16"; 13 | static const char std_msgs_UInt16_md5[] PROGMEM= "1df79edf208b629fe6b81923a544552d"; 14 | class UInt16 : public ros::Msg 15 | { 16 | public: 17 | typedef uint16_t _data_type; 18 | _data_type data; 19 | 20 | UInt16(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 29 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 30 | offset += sizeof(this->data); 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) override 35 | { 36 | int offset = 0; 37 | this->data = ((uint16_t) (*(inbuffer + offset))); 38 | this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 39 | offset += sizeof(this->data); 40 | return offset; 41 | } 42 | 43 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_UInt16_type);return type_msg; }; 44 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_UInt16_md5);return md5_msg; }; 45 | 46 | }; 47 | 48 | } 49 | #endif 50 | -------------------------------------------------------------------------------- /src/std_msgs/UInt32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt32_h 2 | #define _ROS_std_msgs_UInt32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_UInt32_type[] PROGMEM= "std_msgs/UInt32"; 13 | static const char std_msgs_UInt32_md5[] PROGMEM= "304a39449588c7f8ce2df6e8001c5fce"; 14 | class UInt32 : public ros::Msg 15 | { 16 | public: 17 | typedef uint32_t _data_type; 18 | _data_type data; 19 | 20 | UInt32(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 29 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 30 | *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; 31 | *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) override 37 | { 38 | int offset = 0; 39 | this->data = ((uint32_t) (*(inbuffer + offset))); 40 | this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 41 | this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 42 | this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 43 | offset += sizeof(this->data); 44 | return offset; 45 | } 46 | 47 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_UInt32_type);return type_msg; }; 48 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_UInt32_md5);return md5_msg; }; 49 | 50 | }; 51 | 52 | } 53 | #endif 54 | -------------------------------------------------------------------------------- /src/std_msgs/UInt8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt8_h 2 | #define _ROS_std_msgs_UInt8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | static const char std_msgs_UInt8_type[] PROGMEM= "std_msgs/UInt8"; 13 | static const char std_msgs_UInt8_md5[] PROGMEM= "7c8164229e7d2c17eb95e9231617fdee"; 14 | class UInt8 : public ros::Msg 15 | { 16 | public: 17 | typedef uint8_t _data_type; 18 | _data_type data; 19 | 20 | UInt8(): 21 | data(0) 22 | { 23 | } 24 | 25 | virtual int serialize(unsigned char *outbuffer) const override 26 | { 27 | int offset = 0; 28 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 29 | offset += sizeof(this->data); 30 | return offset; 31 | } 32 | 33 | virtual int deserialize(unsigned char *inbuffer) override 34 | { 35 | int offset = 0; 36 | this->data = ((uint8_t) (*(inbuffer + offset))); 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)std_msgs_UInt8_type);return type_msg; }; 42 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)std_msgs_UInt8_md5);return md5_msg; }; 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/tf/tf.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2011, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote prducts derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #ifndef ROS_TF_H_ 36 | #define ROS_TF_H_ 37 | 38 | #include "geometry_msgs/TransformStamped.h" 39 | 40 | namespace tf 41 | { 42 | 43 | static inline geometry_msgs::Quaternion createQuaternionFromYaw(double yaw) 44 | { 45 | geometry_msgs::Quaternion q; 46 | q.x = 0; 47 | q.y = 0; 48 | q.z = sin(yaw * 0.5); 49 | q.w = cos(yaw * 0.5); 50 | return q; 51 | } 52 | 53 | } 54 | 55 | #endif 56 | 57 | -------------------------------------------------------------------------------- /src/tf2_msgs/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 | static const char tf2_msgs_LookupTransformActionGoal_type[] PROGMEM= "tf2_msgs/LookupTransformActionGoal"; 16 | static const char tf2_msgs_LookupTransformActionGoal_md5[] PROGMEM= "f2e7bcdb75c847978d0351a13e699da5"; 17 | class LookupTransformActionGoal : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalID _goal_id_type; 23 | _goal_id_type goal_id; 24 | typedef tf2_msgs::LookupTransformGoal _goal_type; 25 | _goal_type goal; 26 | 27 | LookupTransformActionGoal(): 28 | header(), 29 | goal_id(), 30 | goal() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->goal_id.serialize(outbuffer + offset); 39 | offset += this->goal.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->goal_id.deserialize(inbuffer + offset); 48 | offset += this->goal.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)tf2_msgs_LookupTransformActionGoal_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)tf2_msgs_LookupTransformActionGoal_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformActionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformActionResult_h 2 | #define _ROS_tf2_msgs_LookupTransformActionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "actionlib_msgs/GoalStatus.h" 10 | #include "tf2_msgs/LookupTransformResult.h" 11 | 12 | namespace tf2_msgs 13 | { 14 | 15 | static const char tf2_msgs_LookupTransformActionResult_type[] PROGMEM= "tf2_msgs/LookupTransformActionResult"; 16 | static const char tf2_msgs_LookupTransformActionResult_md5[] PROGMEM= "ac26ce75a41384fa8bb4dc10f491ab90"; 17 | class LookupTransformActionResult : public ros::Msg 18 | { 19 | public: 20 | typedef std_msgs::Header _header_type; 21 | _header_type header; 22 | typedef actionlib_msgs::GoalStatus _status_type; 23 | _status_type status; 24 | typedef tf2_msgs::LookupTransformResult _result_type; 25 | _result_type result; 26 | 27 | LookupTransformActionResult(): 28 | header(), 29 | status(), 30 | result() 31 | { 32 | } 33 | 34 | virtual int serialize(unsigned char *outbuffer) const override 35 | { 36 | int offset = 0; 37 | offset += this->header.serialize(outbuffer + offset); 38 | offset += this->status.serialize(outbuffer + offset); 39 | offset += this->result.serialize(outbuffer + offset); 40 | return offset; 41 | } 42 | 43 | virtual int deserialize(unsigned char *inbuffer) override 44 | { 45 | int offset = 0; 46 | offset += this->header.deserialize(inbuffer + offset); 47 | offset += this->status.deserialize(inbuffer + offset); 48 | offset += this->result.deserialize(inbuffer + offset); 49 | return offset; 50 | } 51 | 52 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)tf2_msgs_LookupTransformActionResult_type);return type_msg; }; 53 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)tf2_msgs_LookupTransformActionResult_md5);return md5_msg; }; 54 | 55 | }; 56 | 57 | } 58 | #endif 59 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformFeedback_h 2 | #define _ROS_tf2_msgs_LookupTransformFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace tf2_msgs 10 | { 11 | 12 | static const char tf2_msgs_LookupTransformFeedback_type[] PROGMEM= "tf2_msgs/LookupTransformFeedback"; 13 | static const char tf2_msgs_LookupTransformFeedback_md5[] PROGMEM= "d41d8cd98f00b204e9800998ecf8427e"; 14 | class LookupTransformFeedback : public ros::Msg 15 | { 16 | public: 17 | 18 | LookupTransformFeedback() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const override 23 | { 24 | int offset = 0; 25 | return offset; 26 | } 27 | 28 | virtual int deserialize(unsigned char *inbuffer) override 29 | { 30 | int offset = 0; 31 | return offset; 32 | } 33 | 34 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)tf2_msgs_LookupTransformFeedback_type);return type_msg; }; 35 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)tf2_msgs_LookupTransformFeedback_md5);return md5_msg; }; 36 | 37 | }; 38 | 39 | } 40 | #endif 41 | -------------------------------------------------------------------------------- /src/tf2_msgs/LookupTransformResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformResult_h 2 | #define _ROS_tf2_msgs_LookupTransformResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/TransformStamped.h" 9 | #include "tf2_msgs/TF2Error.h" 10 | 11 | namespace tf2_msgs 12 | { 13 | 14 | static const char tf2_msgs_LookupTransformResult_type[] PROGMEM= "tf2_msgs/LookupTransformResult"; 15 | static const char tf2_msgs_LookupTransformResult_md5[] PROGMEM= "3fe5db6a19ca9cfb675418c5ad875c36"; 16 | class LookupTransformResult : public ros::Msg 17 | { 18 | public: 19 | typedef geometry_msgs::TransformStamped _transform_type; 20 | _transform_type transform; 21 | typedef tf2_msgs::TF2Error _error_type; 22 | _error_type error; 23 | 24 | LookupTransformResult(): 25 | transform(), 26 | error() 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const override 31 | { 32 | int offset = 0; 33 | offset += this->transform.serialize(outbuffer + offset); 34 | offset += this->error.serialize(outbuffer + offset); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) override 39 | { 40 | int offset = 0; 41 | offset += this->transform.deserialize(inbuffer + offset); 42 | offset += this->error.deserialize(inbuffer + offset); 43 | return offset; 44 | } 45 | 46 | virtual const char * getType(const char * type_msg) override { strcpy_P(type_msg, (char *)tf2_msgs_LookupTransformResult_type);return type_msg; }; 47 | virtual const char * getMD5(const char * md5_msg) override { strcpy_P(md5_msg, (char *)tf2_msgs_LookupTransformResult_md5);return md5_msg; }; 48 | 49 | }; 50 | 51 | } 52 | #endif 53 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "turtle_actionlib/ShapeFeedback.h" 12 | 13 | namespace turtle_actionlib 14 | { 15 | 16 | class ShapeActionFeedback : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef turtle_actionlib::ShapeFeedback _feedback_type; 24 | _feedback_type feedback; 25 | 26 | ShapeActionFeedback(): 27 | header(), 28 | status(), 29 | feedback() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->feedback.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->feedback.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("turtle_actionlib/ShapeActionFeedback");}; 53 | #else 54 | const char * getType() { return PSTR("turtle_actionlib/ShapeActionFeedback");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("aae20e09065c3809e8a8e87c4c8953fd");}; 58 | #else 59 | const char * getMD5() { return PSTR("aae20e09065c3809e8a8e87c4c8953fd");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalID.h" 11 | #include "turtle_actionlib/ShapeGoal.h" 12 | 13 | namespace turtle_actionlib 14 | { 15 | 16 | class ShapeActionGoal : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalID _goal_id_type; 22 | _goal_id_type goal_id; 23 | typedef turtle_actionlib::ShapeGoal _goal_type; 24 | _goal_type goal; 25 | 26 | ShapeActionGoal(): 27 | header(), 28 | goal_id(), 29 | goal() 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 += this->goal_id.serialize(outbuffer + offset); 38 | offset += this->goal.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->goal_id.deserialize(inbuffer + offset); 47 | offset += this->goal.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("turtle_actionlib/ShapeActionGoal");}; 53 | #else 54 | const char * getType() { return PSTR("turtle_actionlib/ShapeActionGoal");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("dbfccd187f2ec9c593916447ffd6cc77");}; 58 | #else 59 | const char * getMD5() { return PSTR("dbfccd187f2ec9c593916447ffd6cc77");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 "ArduinoIncludes.h" 9 | #include "std_msgs/Header.h" 10 | #include "actionlib_msgs/GoalStatus.h" 11 | #include "turtle_actionlib/ShapeResult.h" 12 | 13 | namespace turtle_actionlib 14 | { 15 | 16 | class ShapeActionResult : public ros::Msg 17 | { 18 | public: 19 | typedef std_msgs::Header _header_type; 20 | _header_type header; 21 | typedef actionlib_msgs::GoalStatus _status_type; 22 | _status_type status; 23 | typedef turtle_actionlib::ShapeResult _result_type; 24 | _result_type result; 25 | 26 | ShapeActionResult(): 27 | header(), 28 | status(), 29 | result() 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 += this->status.serialize(outbuffer + offset); 38 | offset += this->result.serialize(outbuffer + offset); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | offset += this->header.deserialize(inbuffer + offset); 46 | offset += this->status.deserialize(inbuffer + offset); 47 | offset += this->result.deserialize(inbuffer + offset); 48 | return offset; 49 | } 50 | 51 | #ifdef ESP8266 52 | const char * getType() { return ("turtle_actionlib/ShapeActionResult");}; 53 | #else 54 | const char * getType() { return PSTR("turtle_actionlib/ShapeActionResult");}; 55 | #endif 56 | #ifdef ESP8266 57 | const char * getMD5() { return ("c8d13d5d140f1047a2e4d3bf5c045822");}; 58 | #else 59 | const char * getMD5() { return PSTR("c8d13d5d140f1047a2e4d3bf5c045822");}; 60 | #endif 61 | 62 | }; 63 | 64 | } 65 | #endif 66 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace turtle_actionlib 11 | { 12 | 13 | class ShapeFeedback : public ros::Msg 14 | { 15 | public: 16 | 17 | ShapeFeedback() 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 | #ifdef ESP8266 34 | const char * getType() { return ("turtle_actionlib/ShapeFeedback");}; 35 | #else 36 | const char * getType() { return PSTR("turtle_actionlib/ShapeFeedback");}; 37 | #endif 38 | #ifdef ESP8266 39 | const char * getMD5() { return ("d41d8cd98f00b204e9800998ecf8427e");}; 40 | #else 41 | const char * getMD5() { return PSTR("d41d8cd98f00b204e9800998ecf8427e");}; 42 | #endif 43 | 44 | }; 45 | 46 | } 47 | #endif 48 | -------------------------------------------------------------------------------- /src/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 | #include "ArduinoIncludes.h" 9 | 10 | namespace turtlesim 11 | { 12 | 13 | class Color : public ros::Msg 14 | { 15 | public: 16 | typedef uint8_t _r_type; 17 | _r_type r; 18 | typedef uint8_t _g_type; 19 | _g_type g; 20 | typedef uint8_t _b_type; 21 | _b_type b; 22 | 23 | Color(): 24 | r(0), 25 | g(0), 26 | b(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const 31 | { 32 | int offset = 0; 33 | *(outbuffer + offset + 0) = (this->r >> (8 * 0)) & 0xFF; 34 | offset += sizeof(this->r); 35 | *(outbuffer + offset + 0) = (this->g >> (8 * 0)) & 0xFF; 36 | offset += sizeof(this->g); 37 | *(outbuffer + offset + 0) = (this->b >> (8 * 0)) & 0xFF; 38 | offset += sizeof(this->b); 39 | return offset; 40 | } 41 | 42 | virtual int deserialize(unsigned char *inbuffer) 43 | { 44 | int offset = 0; 45 | this->r = ((uint8_t) (*(inbuffer + offset))); 46 | offset += sizeof(this->r); 47 | this->g = ((uint8_t) (*(inbuffer + offset))); 48 | offset += sizeof(this->g); 49 | this->b = ((uint8_t) (*(inbuffer + offset))); 50 | offset += sizeof(this->b); 51 | return offset; 52 | } 53 | 54 | #ifdef ESP8266 55 | const char * getType() { return ("turtlesim/Color");}; 56 | #else 57 | const char * getType() { return PSTR("turtlesim/Color");}; 58 | #endif 59 | #ifdef ESP8266 60 | const char * getMD5() { return ("353891e354491c51aabe32df673fb446");}; 61 | #else 62 | const char * getMD5() { return PSTR("353891e354491c51aabe32df673fb446");}; 63 | #endif 64 | 65 | }; 66 | 67 | } 68 | #endif 69 | -------------------------------------------------------------------------------- /update.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | docker build -t ros_serial_update . 4 | 5 | docker run -d --name ros_serial_update ros_serial_update roscore 6 | 7 | docker cp ros_serial_update:/tmp/ros_lib ./ 8 | 9 | docker stop ros_serial_update 10 | 11 | docker rm ros_serial_update 12 | 13 | cp -Rf ./ros_lib/* ./src 14 | 15 | cp -Rf ./ros_lib/examples/* ./examples 16 | 17 | cp -Rf ./ros_lib/tests/* ./extras/tests 18 | 19 | rm -Rf ./src/examples 20 | 21 | rm -Rf ./src/tests 22 | 23 | rm -Rf ./ros_lib --------------------------------------------------------------------------------