Public Member Functions | |
void | get_data (SensorData &data) |
SensorData | get_data () |
bool | initialize () |
MyAhrsDriverForROS (std::string port="", int baud_rate=115200) | |
void | publish_topic (int sensor_id) |
~MyAhrsDriverForROS () | |
Private Member Functions | |
void | OnAttributeChange (int sensor_id, std::string attribute_name, std::string value) |
void | OnSensorData (int sensor_id, SensorData data) |
Private Attributes | |
double | angular_velocity_stddev_ |
tf::TransformBroadcaster | broadcaster_ |
std::string | frame_id_ |
ros::Publisher | imu_data_pub_ |
ros::Publisher | imu_data_raw_pub_ |
ros::Publisher | imu_mag_pub_ |
ros::Publisher | imu_temperature_pub_ |
double | linear_acceleration_stddev_ |
Platform::Mutex | lock_ |
double | magnetic_field_stddev_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_priv_ |
double | orientation_stddev_ |
std::string | parent_frame_id_ |
bool | publish_tf |
SensorData | sensor_data_ |
Definition at line 45 of file myahrs_driver.cpp.
MyAhrsDriverForROS::MyAhrsDriverForROS | ( | std::string | port = "" , |
int | baud_rate = 115200 |
||
) | [inline] |
Definition at line 81 of file myahrs_driver.cpp.
MyAhrsDriverForROS::~MyAhrsDriverForROS | ( | ) | [inline] |
Definition at line 105 of file myahrs_driver.cpp.
void MyAhrsDriverForROS::get_data | ( | SensorData & | data | ) | [inline] |
Reimplemented from WithRobot::iMyAhrsPlus.
Definition at line 128 of file myahrs_driver.cpp.
SensorData MyAhrsDriverForROS::get_data | ( | ) | [inline] |
Reimplemented from WithRobot::iMyAhrsPlus.
Definition at line 134 of file myahrs_driver.cpp.
bool MyAhrsDriverForROS::initialize | ( | ) | [inline] |
Definition at line 108 of file myahrs_driver.cpp.
void MyAhrsDriverForROS::OnAttributeChange | ( | int | sensor_id, |
std::string | attribute_name, | ||
std::string | value | ||
) | [inline, private, virtual] |
Reimplemented from WithRobot::iMyAhrsPlus.
Definition at line 75 of file myahrs_driver.cpp.
void MyAhrsDriverForROS::OnSensorData | ( | int | sensor_id, |
SensorData | data | ||
) | [inline, private, virtual] |
Reimplemented from WithRobot::iMyAhrsPlus.
Definition at line 68 of file myahrs_driver.cpp.
void MyAhrsDriverForROS::publish_topic | ( | int | sensor_id | ) | [inline] |
Definition at line 140 of file myahrs_driver.cpp.
double MyAhrsDriverForROS::angular_velocity_stddev_ [private] |
Definition at line 64 of file myahrs_driver.cpp.
Definition at line 56 of file myahrs_driver.cpp.
std::string MyAhrsDriverForROS::frame_id_ [private] |
Definition at line 62 of file myahrs_driver.cpp.
Definition at line 52 of file myahrs_driver.cpp.
Definition at line 51 of file myahrs_driver.cpp.
Definition at line 53 of file myahrs_driver.cpp.
Definition at line 54 of file myahrs_driver.cpp.
double MyAhrsDriverForROS::linear_acceleration_stddev_ [private] |
Definition at line 63 of file myahrs_driver.cpp.
Platform::Mutex MyAhrsDriverForROS::lock_ [private] |
Definition at line 58 of file myahrs_driver.cpp.
double MyAhrsDriverForROS::magnetic_field_stddev_ [private] |
Definition at line 65 of file myahrs_driver.cpp.
ros::NodeHandle MyAhrsDriverForROS::nh_ [private] |
Definition at line 48 of file myahrs_driver.cpp.
ros::NodeHandle MyAhrsDriverForROS::nh_priv_ [private] |
Definition at line 49 of file myahrs_driver.cpp.
double MyAhrsDriverForROS::orientation_stddev_ [private] |
Definition at line 66 of file myahrs_driver.cpp.
std::string MyAhrsDriverForROS::parent_frame_id_ [private] |
Definition at line 61 of file myahrs_driver.cpp.
bool MyAhrsDriverForROS::publish_tf [private] |
Definition at line 60 of file myahrs_driver.cpp.
SensorData MyAhrsDriverForROS::sensor_data_ [private] |
Definition at line 59 of file myahrs_driver.cpp.