Skip to main content

PoseMessage Struct

ROS Pose message (MessageType::ROS_POSE, version 1). More...

Declaration

struct point_one::fusion_engine::messages::ros::PoseMessage { ... }

Included Headers

Base struct

structMessagePayload

The base class for all message payloads. More...

Public Member Attributes Index

doubleorientation[4] = {NAN, NAN, NAN, NAN}

The platform body orientation with respect to the local ENU frame, represented as a quaternion with the scalar component last (x, y, z, w). More...

Timestampp1_time

The time of the message, in P1 time (beginning at power-on). More...

doubleposition_rel_m[3] = {NAN, NAN, NAN}

The relative change in ENU position since the time of the first PoseMessage, resolved in the local ENU frame at the time of the first PoseMessage. More...

Public Static Attributes Index

static constexpr MessageTypeMESSAGE_TYPE = MessageType::ROS_POSE
static constexpr uint8_tMESSAGE_VERSION = 0

Description

ROS Pose message (MessageType::ROS_POSE, version 1).

See http://docs.ros.org/api/geometry_msgs/html/msg/Pose.html.

Definition at line 43 of file ros.h.

Public Member Attributes

orientation

double point_one::fusion_engine::messages::ros::PoseMessage::orientation[4] = {NAN, NAN, NAN, NAN}

The platform body orientation with respect to the local ENU frame, represented as a quaternion with the scalar component last (x, y, z, w).

Definition at line 71 of file ros.h.

71 double orientation[4] = {NAN, NAN, NAN, NAN};

p1_time

Timestamp point_one::fusion_engine::messages::ros::PoseMessage::p1_time

The time of the message, in P1 time (beginning at power-on).

Definition at line 48 of file ros.h.

position_rel_m

double point_one::fusion_engine::messages::ros::PoseMessage::position_rel_m[3] = {NAN, NAN, NAN}

The relative change in ENU position since the time of the first PoseMessage, resolved in the local ENU frame at the time of the first PoseMessage.

warning

The ROS Pose message API documentation does not currently define the origin or reference frame of its position field. Using the Novatel SPAN driver as a reference (http://docs.ros.org/api/novatel_span_driver/html/publisher_8py_source.html), we have chosen to report a relative ENU position. Absolute world position is available in the GPSFixMessage and messages::PoseMessage classes.

Definition at line 65 of file ros.h.

65 double position_rel_m[3] = {NAN, NAN, NAN};

Public Static Attributes

MESSAGE_TYPE

constexpr MessageType point_one::fusion_engine::messages::ros::PoseMessage::MESSAGE_TYPE = MessageType::ROS_POSE
constexpr static

Definition at line 44 of file ros.h.

44 static constexpr MessageType MESSAGE_TYPE = MessageType::ROS_POSE;

MESSAGE_VERSION

constexpr uint8_t point_one::fusion_engine::messages::ros::PoseMessage::MESSAGE_VERSION = 0
constexpr static

Definition at line 45 of file ros.h.

45 static constexpr uint8_t MESSAGE_VERSION = 0;

The documentation for this struct was generated from the following file:


Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.