#include <Stream.h>
Definition at line 18 of file Stream.h.
◆ CommandType
Enumerator |
---|
GET_IMU | |
GET_QUATERNION | |
GET_ANGULAR_VELOCITY | |
GET_ACCELERATION | |
GET_MAG | |
GET_RPY | |
Definition at line 45 of file Stream.h.
◆ Stream() [1/2]
muse_v2_driver::Stream::Stream |
( |
| ) |
|
|
default |
◆ Stream() [2/2]
muse_v2_driver::Stream::Stream |
( |
ros::NodeHandle & |
node, |
|
|
int |
pub_queue_size = 10 |
|
) |
| |
◆ ~Stream()
muse_v2_driver::Stream::~Stream |
( |
| ) |
|
|
default |
◆ isFrequencyAdmissible()
bool muse_v2_driver::Stream::isFrequencyAdmissible |
( |
int |
frequency | ) |
|
◆ setupInputCommands()
◆ StreamRawData()
void muse_v2_driver::Stream::StreamRawData |
( |
const Transmission::ConstPtr & |
msg, |
|
|
MuseV2 * |
muse_v2 |
|
) |
| |
◆ acceleration_msg
geometry_msgs::Vector3Stamped muse_v2_driver::Stream::acceleration_msg |
◆ angular_velocity_msg
geometry_msgs::Vector3Stamped muse_v2_driver::Stream::angular_velocity_msg |
◆ default_command_list
◆ imu_msg
sensor_msgs::Imu muse_v2_driver::Stream::imu_msg |
◆ input_command
◆ mag_msg
sensor_msgs::MagneticField muse_v2_driver::Stream::mag_msg |
◆ pub_acceleration
◆ pub_angular_velocity
◆ pub_imu
◆ pub_mag
◆ pub_quaternion
◆ pub_rpy
◆ quaternion_msg
geometry_msgs::QuaternionStamped muse_v2_driver::Stream::quaternion_msg |
◆ received_command
◆ rpy_msg
geometry_msgs::Vector3Stamped muse_v2_driver::Stream::rpy_msg |
The documentation for this class was generated from the following files: