34 #ifndef SBG_ROS_CONFIG_STORE_H 35 #define SBG_ROS_CONFIG_STORE_H 118 template <
typename T>
121 if (ref_node_handle.
hasParam(param_key))
124 ref_node_handle.
param<
int>(param_key, parameter, default_value);
126 return static_cast<T
>(parameter);
130 return static_cast<T
>(default_value);
411 #endif // SBG_ROS_CONFIG_STORE_H const SbgEComInitConditionConf & getInitialConditions(void) const
SbgEComOutputPort m_output_port_
SbgEComSensorAlignmentInfo m_sensor_alignement_info_
SbgEComOutputMode output_mode
sbgIpAddress getIpAddress(void) const
uint32_t m_out_port_address_
const std::string & getUartPortName(void) const
const std::vector< SbgLogOutput > & getOutputModes(void) const
uint32_t m_uart_baud_rate_
enum _SbgEComMagCalibMode SbgEComMagCalibMode
void loadCommunicationParameters(const ros::NodeHandle &ref_node_handle)
const SbgEComGnssInstallation & getGnssInstallation(void) const
void loadOdometerParameters(const ros::NodeHandle &ref_node_handle)
SbgEComGnssRejectionConf m_gnss_rejection_conf_
SbgEComMagCalibBandwidth m_mag_calib_bandwidth_
const SbgEComMagCalibBandwidth & getMagnetometerCalibBandwidth(void) const
uint32_t m_in_port_address_
enum _SbgEComMagCalibBandwidth SbgEComMagCalibBandwidth
uint32_t getReadingRateFrequency(void) const
const SbgEComGnssRejectionConf & getGnssRejection(void) const
const SbgEComMagCalibMode & getMagnetometerCalibMode(void) const
SbgEComModelInfo m_gnss_model_info_
bool m_configure_through_ros_
bool checkConfigWithRos(void) const
const SbgEComModelInfo & getMotionProfile(void) const
T getParameter(const ros::NodeHandle &ref_node_handle, std::string param_key, int default_value) const
std::vector< SbgLogOutput > m_output_modes_
void loadGnssParameters(const ros::NodeHandle &ref_node_handle)
bool m_upd_communication_
void loadAidingAssignementParameters(const ros::NodeHandle &ref_node_handle)
SbgVector3< float > m_odometer_level_arm_
SbgEComModelInfo m_motion_profile_model_info_
SbgEComOdoRejectionConf m_odometer_rejection_conf_
const SbgVector3< float > & getOdometerLevelArms(void) const
bool m_serial_communication_
SbgEComOdoConf m_odometer_conf_
void loadOutputConfiguration(const ros::NodeHandle &ref_node_handle, const std::string &ref_key, SbgEComClass sbg_msg_class, SbgEComMsgId sbg_msg_id)
uint32_t getBaudRate(void) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const SbgEComMagRejectionConf & getMagnetometerRejection(void) const
uint32_t getInputPortAddress(void) const
SbgEComMagRejectionConf m_mag_rejection_conf_
void loadSensorParameters(const ros::NodeHandle &ref_node_handle)
void loadFromRosNodeHandle(const ros::NodeHandle &ref_node_handle)
SbgVector3< float > m_sensor_lever_arm_
const SbgEComModelInfo & getMagnetometerModel(void) const
SbgEComMagCalibMode m_mag_calib_mode_
uint32_t getOutputPortAddress(void) const
sbgIpAddress m_sbg_ip_address_
void loadMagnetometersParameters(const ros::NodeHandle &ref_node_handle)
void loadImuAlignementParameters(const ros::NodeHandle &ref_node_handle)
const SbgEComOdoConf & getOdometerConf(void) const
bool isInterfaceUdp(void) const
const SbgVector3< float > & getSensorLevelArms(void) const
const SbgEComAidingAssignConf & getAidingAssignement(void) const
std::string m_uart_port_name_
const SbgEComOdoRejectionConf & getOdometerRejection(void) const
enum _SbgEComOutputPort SbgEComOutputPort
bool isInterfaceSerial(void) const
SbgEComClass message_class
enum _SbgEComClass SbgEComClass
SbgEComAidingAssignConf m_aiding_assignement_conf_
bool hasParam(const std::string &key) const
Handle a three components vector.
enum _SbgEComOutputMode SbgEComOutputMode
bool m_ros_standard_output_
const SbgEComModelInfo & getGnssModel(void) const
SbgEComGnssInstallation m_gnss_installation_
SbgEComOutputPort getOutputPort(void) const
SbgEComInitConditionConf m_init_condition_conf_
SbgEComModelInfo m_mag_model_info_
Main header file for the SBG Systems Enhanced Communication Library.
const SbgEComSensorAlignmentInfo & getSensorAlignement(void) const
uint32_t m_rate_frequency_
bool checkRosStandardMessages(void) const