// Auto-generated. Do not edit! // (in-package waterplus_map_tools.srv) "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 AddNewWaypointRequest { constructor(initObj={}) { if (initObj === null) { // initObj === null is a special case for deserialization where we don't initialize fields this.name = null; this.pose = null; } else { 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 AddNewWaypointRequest // 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 AddNewWaypointRequest let len; let data = new AddNewWaypointRequest(null); // 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.name); return length + 60; } static datatype() { // Returns string type for a service object return 'waterplus_map_tools/AddNewWaypointRequest'; } static md5sum() { //Returns md5sum for a message object return '177d54286ddeee12eba514054bddffd5'; } static messageDefinition() { // Returns full string definition for message return ` 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 AddNewWaypointRequest(null); 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; } }; class AddNewWaypointResponse { constructor(initObj={}) { if (initObj === null) { // initObj === null is a special case for deserialization where we don't initialize fields this.result = null; } else { if (initObj.hasOwnProperty('result')) { this.result = initObj.result } else { this.result = false; } } } static serialize(obj, buffer, bufferOffset) { // Serializes a message object of type AddNewWaypointResponse // Serialize message field [result] bufferOffset = _serializer.bool(obj.result, buffer, bufferOffset); return bufferOffset; } static deserialize(buffer, bufferOffset=[0]) { //deserializes a message object of type AddNewWaypointResponse let len; let data = new AddNewWaypointResponse(null); // Deserialize message field [result] data.result = _deserializer.bool(buffer, bufferOffset); return data; } static getMessageSize(object) { return 1; } static datatype() { // Returns string type for a service object return 'waterplus_map_tools/AddNewWaypointResponse'; } static md5sum() { //Returns md5sum for a message object return 'eb13ac1f1354ccecb7941ee8fa2192e8'; } static messageDefinition() { // Returns full string definition for message return ` bool result `; } 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 AddNewWaypointResponse(null); if (msg.result !== undefined) { resolved.result = msg.result; } else { resolved.result = false } return resolved; } }; module.exports = { Request: AddNewWaypointRequest, Response: AddNewWaypointResponse, md5sum() { return '6948a8f076727d2b3b462b6ca2b31b5f'; }, datatype() { return 'waterplus_map_tools/AddNewWaypoint'; } };