#include <quaternion_msg.h>
|
| void | parseMessageImpl (const geometry_msgs::msg::Quaternion &msg, double ×tamp) override |
| |
| void | parseMessageImpl (const geometry_msgs::Quaternion &msg, double ×tamp) override |
| |
| | QuaternionMsgParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| | QuaternionMsgParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| | BuiltinMessageParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| | BuiltinMessageParser (const std::string &topic_name, PlotDataMapRef &plot_data) |
| |
| bool | parseMessage (MessageRef serialized_msg, double ×tamp) override |
| |
| virtual bool | parseMessage (MessageRef serialized_msg, double ×tamp) |
| |
| | Ros2MessageParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| const rosidl_message_type_support_t * | typeSupport () const |
| |
| const RosParserConfig & | getConfig () const |
| |
| PJ::PlotData & | getSeries (const std::string &key) |
| |
| PJ::StringSeries & | getStringSeries (const std::string &key) |
| |
| | RosMessageParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| void | setConfig (const RosParserConfig &config) |
| |
| bool | clampLargeArray () const |
| |
| unsigned | maxArraySize () const |
| |
| | MessageParser (const std::string &topic_name, PlotDataMapRef &plot_data) |
| |
| virtual bool | parseMessage (const MessageRef serialized_msg, double ×tamp)=0 |
| |
| virtual void | setLargeArraysPolicy (bool clamp, unsigned max_size) |
| |
| virtual | ~MessageParser ()=default |
| |
| | BuiltinMessageParser (const std::string &topic_name, PJ::PlotDataMapRef &plot_data) |
| |
| | BuiltinMessageParser (const std::string &topic_name, PlotDataMapRef &plot_data) |
| |
| bool | parseMessage (MessageRef serialized_msg, double ×tamp) override |
| |
| virtual bool | parseMessage (MessageRef serialized_msg, double ×tamp) |
| |
◆ QuaternionMsgParser() [1/2]
| QuaternionMsgParser::QuaternionMsgParser |
( |
const std::string & |
topic_name, |
|
|
PJ::PlotDataMapRef & |
plot_data |
|
) |
| |
|
inline |
◆ QuaternionMsgParser() [2/2]
| QuaternionMsgParser::QuaternionMsgParser |
( |
const std::string & |
topic_name, |
|
|
PJ::PlotDataMapRef & |
plot_data |
|
) |
| |
|
inline |
◆ parseMessageImpl() [1/2]
| void QuaternionMsgParser::parseMessageImpl |
( |
const geometry_msgs::msg::Quaternion & |
msg, |
|
|
double & |
timestamp |
|
) |
| |
|
inlineoverridevirtual |
◆ parseMessageImpl() [2/2]
| void QuaternionMsgParser::parseMessageImpl |
( |
const geometry_msgs::Quaternion & |
msg, |
|
|
double & |
timestamp |
|
) |
| |
|
inlineoverridevirtual |
◆ _data
◆ _initialized
| bool QuaternionMsgParser::_initialized = false |
|
private |
◆ _pitch_offset
| double QuaternionMsgParser::_pitch_offset |
|
private |
◆ _prev_pitch
| double QuaternionMsgParser::_prev_pitch |
|
private |
◆ _prev_roll
| double QuaternionMsgParser::_prev_roll |
|
private |
◆ _prev_yaw
| double QuaternionMsgParser::_prev_yaw |
|
private |
◆ _roll_offset
| double QuaternionMsgParser::_roll_offset |
|
private |
◆ _yaw_offset
| double QuaternionMsgParser::_yaw_offset |
|
private |
The documentation for this class was generated from the following file: