| 123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151 |
- // Auto-generated. Do not edit!
- // (in-package waterplus_map_tools.msg)
- "use strict";
- const _serializer = _ros_msg_utils.Serialize;
- const _arraySerializer = _serializer.Array;
- const _deserializer = _ros_msg_utils.Deserialize;
- const _arrayDeserializer = _deserializer.Array;
- const _finder = _ros_msg_utils.Find;
- const _getByteLength = _ros_msg_utils.getByteLength;
- let geometry_msgs = _finder('geometry_msgs');
- //-----------------------------------------------------------
- class Waypoint {
- constructor(initObj={}) {
- if (initObj === null) {
- // initObj === null is a special case for deserialization where we don't initialize fields
- this.frame_id = null;
- this.name = null;
- this.pose = null;
- }
- else {
- if (initObj.hasOwnProperty('frame_id')) {
- this.frame_id = initObj.frame_id
- }
- else {
- this.frame_id = '';
- }
- if (initObj.hasOwnProperty('name')) {
- this.name = initObj.name
- }
- else {
- this.name = '';
- }
- if (initObj.hasOwnProperty('pose')) {
- this.pose = initObj.pose
- }
- else {
- this.pose = new geometry_msgs.msg.Pose();
- }
- }
- }
- static serialize(obj, buffer, bufferOffset) {
- // Serializes a message object of type Waypoint
- // Serialize message field [frame_id]
- bufferOffset = _serializer.string(obj.frame_id, buffer, bufferOffset);
- // Serialize message field [name]
- bufferOffset = _serializer.string(obj.name, buffer, bufferOffset);
- // Serialize message field [pose]
- bufferOffset = geometry_msgs.msg.Pose.serialize(obj.pose, buffer, bufferOffset);
- return bufferOffset;
- }
- static deserialize(buffer, bufferOffset=[0]) {
- //deserializes a message object of type Waypoint
- let len;
- let data = new Waypoint(null);
- // Deserialize message field [frame_id]
- data.frame_id = _deserializer.string(buffer, bufferOffset);
- // Deserialize message field [name]
- data.name = _deserializer.string(buffer, bufferOffset);
- // Deserialize message field [pose]
- data.pose = geometry_msgs.msg.Pose.deserialize(buffer, bufferOffset);
- return data;
- }
- static getMessageSize(object) {
- let length = 0;
- length += _getByteLength(object.frame_id);
- length += _getByteLength(object.name);
- return length + 64;
- }
- static datatype() {
- // Returns string type for a message object
- return 'waterplus_map_tools/Waypoint';
- }
- static md5sum() {
- //Returns md5sum for a message object
- return 'b5abd84eafa003e99e40f2565ee73135';
- }
- static messageDefinition() {
- // Returns full string definition for message
- return `
- string frame_id
- string name
- geometry_msgs/Pose pose
- ================================================================================
- MSG: geometry_msgs/Pose
- # A representation of pose in free space, composed of position and orientation.
- Point position
- Quaternion orientation
-
- ================================================================================
- MSG: geometry_msgs/Point
- # This contains the position of a point in free space
- float64 x
- float64 y
- float64 z
-
- ================================================================================
- MSG: geometry_msgs/Quaternion
- # This represents an orientation in free space in quaternion form.
-
- float64 x
- float64 y
- float64 z
- float64 w
-
- `;
- }
- static Resolve(msg) {
- // deep-construct a valid message object instance of whatever was passed in
- if (typeof msg !== 'object' || msg === null) {
- msg = {};
- }
- const resolved = new Waypoint(null);
- if (msg.frame_id !== undefined) {
- resolved.frame_id = msg.frame_id;
- }
- else {
- resolved.frame_id = ''
- }
- if (msg.name !== undefined) {
- resolved.name = msg.name;
- }
- else {
- resolved.name = ''
- }
- if (msg.pose !== undefined) {
- resolved.pose = geometry_msgs.msg.Pose.Resolve(msg.pose)
- }
- else {
- resolved.pose = new geometry_msgs.msg.Pose()
- }
- return resolved;
- }
- };
- module.exports = Waypoint;
|