Classes | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
WithRobot::iMyAhrsPlus Class Reference

#include <myahrs_plus.hpp>

Inheritance diagram for WithRobot::iMyAhrsPlus:
Inheritance graph
[legend]

Classes

class  EventItem
 
class  EventQueue
 
class  Protocol
 
class  ResponsQueue
 

Public Member Functions

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 ()
 

Protected Member Functions

virtual void OnAttributeChange (int sensor_id, std::string attribute_name, std::string value)
 
virtual void OnSensorData (int sensor_id, SensorData sensor_data)
 

Private Types

typedef bool(iMyAhrsPlus::* AscHandler) (std::vector< std::string > &tokens)
 
typedef bool(iMyAhrsPlus::* AscRspHandler) (std::map< std::string, std::string > &attributes)
 
typedef bool(iMyAhrsPlus::* BinHandler) (iNodeParser::Node &node)
 

Private Member Functions

bool ascii_parse_response (std::vector< std::string > &tokens)
 
bool ascii_rsp_asc_out (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_baudrate (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_bin_out (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_calib (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_divider (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_factory (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_id (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_mode (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_ping (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_save (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_sensitivity (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_serial_number (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_stat (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_trigger (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_user_orientation (std::map< std::string, std::string > &attributes)
 
bool ascii_rsp_version (std::map< std::string, std::string > &attributes)
 
bool ascii_update_euler (std::vector< std::string > &tokens)
 
bool ascii_update_imu (std::vector< std::string > &tokens)
 
bool ascii_update_quaternion (std::vector< std::string > &tokens)
 
bool ascii_update_quatimu (std::vector< std::string > &tokens)
 
bool ascii_update_riimu (std::vector< std::string > &tokens)
 
bool ascii_update_rpyimu (std::vector< std::string > &tokens)
 
bool binary_parse_response (std::vector< iNodeParser::Node > &node_list)
 
bool binary_update_euler (iNodeParser::Node &node)
 
bool binary_update_imu (iNodeParser::Node &node)
 
bool binary_update_quaternion (iNodeParser::Node &node)
 
bool binary_update_riimu (iNodeParser::Node &node)
 
bool binary_update_sequence (iNodeParser::Node &node)
 
void clear_all_attribute ()
 
void dbg_show_all_attributes (std::map< std::string, std::string > &attributes)
 
 iMyAhrsPlus (iMyAhrsPlus &rhs)
 
float int16tofloat (int16_t value, float value_max)
 
bool is_exist (const std::string &attribute_name)
 
void proc_callback ()
 
void proc_receiver ()
 
bool send_command (std::string command_string, int timeout_msec)
 
void set_attribute (const std::string &attribute_name, const std::string &value)
 

Static Private Member Functions

static void * thread_proc_callback (void *arg)
 
static void * thread_proc_receiver (void *arg)
 

Private Attributes

bool activate_user_event
 
std::map< std::string, AscHandlerascii_handler_data_map
 
std::map< std::string, AscRspHandlerascii_handler_rsp_map
 
std::map< std::string, std::string > attribute_map
 
std::map< std::string, BinHandlerbinary_handler_data_map
 
bool debug
 
class WithRobot::iMyAhrsPlus::EventQueue event_queue
 
Platform::Mutex mutex_attribute
 
Platform::Mutex mutex_communication
 
WithRobot::iMyAhrsPlus::Protocol protocol
 
class WithRobot::iMyAhrsPlus::ResponsQueue response_message_queue
 
SensorData sensor_data
 
int sensor_id
 
Platform::SerialPort serial
 
Platform::Thread thread_event
 
Platform::Thread thread_receiver
 
bool thread_receiver_ready
 

Static Private Attributes

static const int ACCEL_RANGE = 16
 
static const int EULER_RANGE = 180
 
static const int GYRO_RANGE = 2000
 
static const int MAGNET_RANGE = 300
 
static const int TEMP_RANGE = 200
 

Detailed Description

Definition at line 1634 of file myahrs_plus.hpp.

Member Typedef Documentation

typedef bool(iMyAhrsPlus::* WithRobot::iMyAhrsPlus::AscHandler) (std::vector< std::string > &tokens)
private

Definition at line 1654 of file myahrs_plus.hpp.

typedef bool(iMyAhrsPlus::* WithRobot::iMyAhrsPlus::AscRspHandler) (std::map< std::string, std::string > &attributes)
private

Definition at line 1657 of file myahrs_plus.hpp.

typedef bool(iMyAhrsPlus::* WithRobot::iMyAhrsPlus::BinHandler) (iNodeParser::Node &node)
private

Definition at line 1660 of file myahrs_plus.hpp.

Constructor & Destructor Documentation

WithRobot::iMyAhrsPlus::iMyAhrsPlus ( iMyAhrsPlus rhs)
inlineprivate

Definition at line 1837 of file myahrs_plus.hpp.

WithRobot::iMyAhrsPlus::iMyAhrsPlus ( std::string  port_name = "",
unsigned int  baudrate = 115200 
)
inline

Definition at line 1840 of file myahrs_plus.hpp.

virtual WithRobot::iMyAhrsPlus::~iMyAhrsPlus ( )
inlinevirtual

Definition at line 1893 of file myahrs_plus.hpp.

Member Function Documentation

bool WithRobot::iMyAhrsPlus::ascii_parse_response ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2456 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_asc_out ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2512 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_baudrate ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2643 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_bin_out ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2520 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_calib ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2552 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_divider ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2495 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_factory ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2590 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_id ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2614 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_mode ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2504 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_ping ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2491 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_save ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2651 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_sensitivity ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2632 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_serial_number ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2624 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_stat ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2596 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_trigger ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2487 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_user_orientation ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2530 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_rsp_version ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2602 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_euler ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2663 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_imu ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2785 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_quaternion ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2684 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_quatimu ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2734 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_riimu ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2764 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::ascii_update_rpyimu ( std::vector< std::string > &  tokens)
inlineprivate

Definition at line 2705 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_parse_response ( std::vector< iNodeParser::Node > &  node_list)
inlineprivate

Definition at line 2809 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_update_euler ( iNodeParser::Node node)
inlineprivate

Definition at line 2851 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_update_imu ( iNodeParser::Node node)
inlineprivate

Definition at line 2890 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_update_quaternion ( iNodeParser::Node node)
inlineprivate

Definition at line 2870 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_update_riimu ( iNodeParser::Node node)
inlineprivate

Definition at line 2925 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::binary_update_sequence ( iNodeParser::Node node)
inlineprivate

Definition at line 2843 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::clear_all_attribute ( )
inlineprivate

Definition at line 1998 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_ascii_data_format ( const char *  asc_output = 0,
int  timeout_msec = 500 
)
inline

Definition at line 2163 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_baudrate ( int  timeout_msec = 500)
inline

Definition at line 2240 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_baudrate ( const char *  baudrate,
int  timeout_msec = 500 
)
inline

Definition at line 2244 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_binary_data_format ( const char *  bin_output = 0,
int  timeout_msec = 500 
)
inline

Definition at line 2173 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_calibration_parameter ( char  sensor_type,
const char *  calibration_parameters = 0,
int  timeout_msec = 500 
)
inline

Definition at line 2196 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_clear_user_orientation_offset ( int  timeout_msec = 500)
inline

Definition at line 2192 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_divider ( int  timeout_msec = 500)
inline

Definition at line 2140 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_divider ( const char *  divider,
int  timeout_msec = 500 
)
inline

Definition at line 2144 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_id ( int  timeout_msec = 500)
inline

Definition at line 2219 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_id ( const char *  str_sensor_id,
int  timeout_msec = 500 
)
inline

Definition at line 2223 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_mode ( const char *  mode_string = 0,
int  timeout_msec = 500 
)
inline

Definition at line 2153 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_ping ( int  timeout_msec = 500)
inline

Definition at line 2136 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_restore_all_default ( int  timeout_msec = 500)
inline

Definition at line 2211 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_save ( int  timeout_msec = 500)
inline

Definition at line 2253 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_sensitivity ( int  timeout_msec = 500)
inline

Definition at line 2236 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_serial_number ( int  timeout_msec = 500)
inline

Definition at line 2232 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_set_user_orientation_offset ( int  timeout_msec = 500)
inline

Definition at line 2183 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_set_user_orientation_offset ( const char *  enable_yaw_offset,
int  timeout_msec = 500 
)
inline

Definition at line 2187 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::cmd_trigger ( )
inline

Definition at line 2131 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::cmd_version ( int  timeout_msec = 500)
inline

Definition at line 2215 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::dbg_show_all_attributes ( std::map< std::string, std::string > &  attributes)
inlineprivate

Definition at line 2481 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::get_attribute ( const char *  attrib_name,
std::string &  attrib_value 
)
inline

Definition at line 1963 of file myahrs_plus.hpp.

std::vector<std::string> WithRobot::iMyAhrsPlus::get_attribute_list ( )
inline

Definition at line 2033 of file myahrs_plus.hpp.

SensorData WithRobot::iMyAhrsPlus::get_data ( )
inline

Definition at line 1950 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::get_data ( SensorData data)
inline

Definition at line 1955 of file myahrs_plus.hpp.

int WithRobot::iMyAhrsPlus::get_sensor_id ( )
inline

Definition at line 1945 of file myahrs_plus.hpp.

float WithRobot::iMyAhrsPlus::int16tofloat ( int16_t  value,
float  value_max 
)
inlineprivate

Definition at line 2837 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::is_exist ( const std::string &  attribute_name)
inlineprivate

Definition at line 1978 of file myahrs_plus.hpp.

virtual void WithRobot::iMyAhrsPlus::OnAttributeChange ( int  sensor_id,
std::string  attribute_name,
std::string  value 
)
inlineprotectedvirtual

Reimplemented in WithRobot::MyAhrsPlus, and MyAhrsDriverForROS.

Definition at line 2262 of file myahrs_plus.hpp.

virtual void WithRobot::iMyAhrsPlus::OnSensorData ( int  sensor_id,
SensorData  sensor_data 
)
inlineprotectedvirtual

Reimplemented in WithRobot::MyAhrsPlus, and MyAhrsDriverForROS.

Definition at line 2261 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::proc_callback ( )
inlineprivate

Definition at line 2401 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::proc_receiver ( )
inlineprivate

Definition at line 2376 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::resync ( )
inline

Definition at line 2045 of file myahrs_plus.hpp.

const char* WithRobot::iMyAhrsPlus::sdk_version ( )
inline

Definition at line 1899 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::send_command ( std::string  command_string,
int  timeout_msec 
)
inlineprivate

Definition at line 2265 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::set_attribute ( const std::string &  attribute_name,
const std::string &  value 
)
inlineprivate

Definition at line 1988 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::start ( std::string  port_name = "",
int  baudrate = -1 
)
inline

Definition at line 1903 of file myahrs_plus.hpp.

void WithRobot::iMyAhrsPlus::stop ( )
inline

Definition at line 1937 of file myahrs_plus.hpp.

static void* WithRobot::iMyAhrsPlus::thread_proc_callback ( void *  arg)
inlinestaticprivate

Definition at line 2447 of file myahrs_plus.hpp.

static void* WithRobot::iMyAhrsPlus::thread_proc_receiver ( void *  arg)
inlinestaticprivate

Definition at line 2442 of file myahrs_plus.hpp.

Member Data Documentation

const int WithRobot::iMyAhrsPlus::ACCEL_RANGE = 16
staticprivate

Definition at line 1663 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::activate_user_event
private

Definition at line 1646 of file myahrs_plus.hpp.

std::map<std::string, AscHandler> WithRobot::iMyAhrsPlus::ascii_handler_data_map
private

Definition at line 1655 of file myahrs_plus.hpp.

std::map<std::string, AscRspHandler> WithRobot::iMyAhrsPlus::ascii_handler_rsp_map
private

Definition at line 1658 of file myahrs_plus.hpp.

std::map<std::string, std::string> WithRobot::iMyAhrsPlus::attribute_map
private

Definition at line 1652 of file myahrs_plus.hpp.

std::map<std::string, BinHandler> WithRobot::iMyAhrsPlus::binary_handler_data_map
private

Definition at line 1661 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::debug
private

Definition at line 1636 of file myahrs_plus.hpp.

const int WithRobot::iMyAhrsPlus::EULER_RANGE = 180
staticprivate

Definition at line 1667 of file myahrs_plus.hpp.

class WithRobot::iMyAhrsPlus::EventQueue WithRobot::iMyAhrsPlus::event_queue
private
const int WithRobot::iMyAhrsPlus::GYRO_RANGE = 2000
staticprivate

Definition at line 1664 of file myahrs_plus.hpp.

const int WithRobot::iMyAhrsPlus::MAGNET_RANGE = 300
staticprivate

Definition at line 1665 of file myahrs_plus.hpp.

Platform::Mutex WithRobot::iMyAhrsPlus::mutex_attribute
private

Definition at line 1640 of file myahrs_plus.hpp.

Platform::Mutex WithRobot::iMyAhrsPlus::mutex_communication
private

Definition at line 1641 of file myahrs_plus.hpp.

WithRobot::iMyAhrsPlus::Protocol WithRobot::iMyAhrsPlus::protocol
private
class WithRobot::iMyAhrsPlus::ResponsQueue WithRobot::iMyAhrsPlus::response_message_queue
private
SensorData WithRobot::iMyAhrsPlus::sensor_data
private

Definition at line 1649 of file myahrs_plus.hpp.

int WithRobot::iMyAhrsPlus::sensor_id
private

Definition at line 1651 of file myahrs_plus.hpp.

Platform::SerialPort WithRobot::iMyAhrsPlus::serial
private

Definition at line 1638 of file myahrs_plus.hpp.

const int WithRobot::iMyAhrsPlus::TEMP_RANGE = 200
staticprivate

Definition at line 1666 of file myahrs_plus.hpp.

Platform::Thread WithRobot::iMyAhrsPlus::thread_event
private

Definition at line 1647 of file myahrs_plus.hpp.

Platform::Thread WithRobot::iMyAhrsPlus::thread_receiver
private

Definition at line 1644 of file myahrs_plus.hpp.

bool WithRobot::iMyAhrsPlus::thread_receiver_ready
private

Definition at line 1643 of file myahrs_plus.hpp.


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