Class RosbotImuSensor

Inheritance Relationships

Base Type

  • public hardware_interface::SensorInterface

Class Documentation

class RosbotImuSensor : public hardware_interface::SensorInterface

Public Functions

ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_init (const hardware_interface::HardwareInfo &hardware_info) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
ROSBOT_HARDWARE_INTERFACES_PUBLIC std::vector< StateInterface > export_state_interfaces () override
ROSBOT_HARDWARE_INTERFACES_PUBLIC return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override

Protected Functions

void cleanup_node()
void imu_cb(const std::shared_ptr<Imu> msg)

Protected Attributes

realtime_tools::RealtimeThreadSafeBox<std::shared_ptr<Imu>> received_imu_msg_ptr_ = {nullptr}
rclcpp::Subscription<Imu>::SharedPtr imu_subscriber_ = nullptr
std::vector<double> imu_sensor_state_
bool subscriber_is_active_ = false
std::shared_ptr<rclcpp::Node> node_
rclcpp::executors::MultiThreadedExecutor executor_
std::unique_ptr<std::thread> executor_thread_
uint connection_check_period_ms_
uint connection_timeout_ms_