Class ImuStateCheckerRos2

Class Documentation

class ImuStateCheckerRos2

Checks state of IMU (STANDSTILL or MOVING)

Public Functions

ImuStateCheckerRos2(const rclcpp::Node::SharedPtr &node)

Constructor for StateChecker.

~ImuStateCheckerRos2()

Destructor for StateChecker.

e_imu_state evaluateState(const sensor_msgs::msg::Imu::SharedPtr imu_msg)

Evaluates that state of the IMU based on the standard deviation of the magnitude.

Parameters:

im_msg[in] The IMU data that will be evaluated

Returns:

state of the IMU

void imuCallback(const sensor_msgs::msg::Imu::SharedPtr msg)

Callback when IMU topic is received.

Parameters:

msg[in] The IMU data (sensor_msgs)

void imuCallback(const adrd2121_imu::msg::AdiImu::SharedPtr msg)

Callback when IMU topic is received.

Parameters:

msg[in] The IMU data (AdiImu)

float getStandardDev(std::deque<float> data)

Calculates the standard deviation.

Parameters:

data[in] The deque of data

Returns:

The computed standard deviation

void evaluateStandstillBegin(void)

Gets the Time Start when IMU is STANDSTILL.

rclcpp::Time getStandstillBegin(void)

Returns the Time Start when IMU is STANDSTILL.

Returns:

value of standstill_begin_

e_imu_state getState(void)

Returns the current state.

Returns:

value of state_

bool loadParams(void)

Loads parameters for the IMU state checker.

Returns:

Boolean if successful (true) or not (false)

bool init(void)

Initialize imu/data_raw subscription and publisher of imu_state.

Returns:

Boolean if successful (true) or not (false)