Public Member Functions | Private Member Functions | Private Attributes | List of all members
MyAhrsDriverForROS Class Reference
Inheritance diagram for MyAhrsDriverForROS:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from WithRobot::iMyAhrsPlus
bool cmd_ascii_data_format (const char *asc_output=0, int timeout_msec=500)
 
bool cmd_baudrate (int timeout_msec=500)
 
bool cmd_baudrate (const char *baudrate, int timeout_msec=500)
 
bool cmd_binary_data_format (const char *bin_output=0, int timeout_msec=500)
 
bool cmd_calibration_parameter (char sensor_type, const char *calibration_parameters=0, int timeout_msec=500)
 
bool cmd_clear_user_orientation_offset (int timeout_msec=500)
 
bool cmd_divider (int timeout_msec=500)
 
bool cmd_divider (const char *divider, int timeout_msec=500)
 
bool cmd_id (int timeout_msec=500)
 
bool cmd_id (const char *str_sensor_id, int timeout_msec=500)
 
bool cmd_mode (const char *mode_string=0, int timeout_msec=500)
 
bool cmd_ping (int timeout_msec=500)
 
bool cmd_restore_all_default (int timeout_msec=500)
 
bool cmd_save (int timeout_msec=500)
 
bool cmd_sensitivity (int timeout_msec=500)
 
bool cmd_serial_number (int timeout_msec=500)
 
bool cmd_set_user_orientation_offset (int timeout_msec=500)
 
bool cmd_set_user_orientation_offset (const char *enable_yaw_offset, int timeout_msec=500)
 
void cmd_trigger ()
 
bool cmd_version (int timeout_msec=500)
 
bool get_attribute (const char *attrib_name, std::string &attrib_value)
 
std::vector< std::string > get_attribute_list ()
 
SensorData get_data ()
 
void get_data (SensorData &data)
 
int get_sensor_id ()
 
 iMyAhrsPlus (std::string port_name="", unsigned int baudrate=115200)
 
bool resync ()
 
const char * sdk_version ()
 
bool start (std::string port_name="", int baudrate=-1)
 
void stop ()
 
virtual ~iMyAhrsPlus ()
 

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_
 
SensorData sensor_data_
 

Additional Inherited Members

Detailed Description

Definition at line 45 of file myahrs_driver.cpp.

Constructor & Destructor Documentation

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 104 of file myahrs_driver.cpp.

Member Function Documentation

void MyAhrsDriverForROS::get_data ( SensorData data)
inline

Definition at line 127 of file myahrs_driver.cpp.

SensorData MyAhrsDriverForROS::get_data ( )
inline

Definition at line 133 of file myahrs_driver.cpp.

bool MyAhrsDriverForROS::initialize ( )
inline

Definition at line 107 of file myahrs_driver.cpp.

void MyAhrsDriverForROS::OnAttributeChange ( int  sensor_id,
std::string  attribute_name,
std::string  value 
)
inlineprivatevirtual

Reimplemented from WithRobot::iMyAhrsPlus.

Definition at line 75 of file myahrs_driver.cpp.

void MyAhrsDriverForROS::OnSensorData ( int  sensor_id,
SensorData  data 
)
inlineprivatevirtual

Reimplemented from WithRobot::iMyAhrsPlus.

Definition at line 68 of file myahrs_driver.cpp.

void MyAhrsDriverForROS::publish_topic ( int  sensor_id)
inline

Definition at line 139 of file myahrs_driver.cpp.

Member Data Documentation

double MyAhrsDriverForROS::angular_velocity_stddev_
private

Definition at line 64 of file myahrs_driver.cpp.

tf::TransformBroadcaster MyAhrsDriverForROS::broadcaster_
private

Definition at line 56 of file myahrs_driver.cpp.

std::string MyAhrsDriverForROS::frame_id_
private

Definition at line 62 of file myahrs_driver.cpp.

ros::Publisher MyAhrsDriverForROS::imu_data_pub_
private

Definition at line 52 of file myahrs_driver.cpp.

ros::Publisher MyAhrsDriverForROS::imu_data_raw_pub_
private

Definition at line 51 of file myahrs_driver.cpp.

ros::Publisher MyAhrsDriverForROS::imu_mag_pub_
private

Definition at line 53 of file myahrs_driver.cpp.

ros::Publisher MyAhrsDriverForROS::imu_temperature_pub_
private

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.

SensorData MyAhrsDriverForROS::sensor_data_
private

Definition at line 59 of file myahrs_driver.cpp.


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


myahrs_driver
Author(s): Yoonseok Pyo
autogenerated on Thu Jul 16 2020 03:08:51