Skip to content

Commit

Permalink
Moving away from custom message
Browse files Browse the repository at this point in the history
  • Loading branch information
chacalnoir committed Dec 6, 2023
1 parent d488056 commit 3687999
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 16 deletions.
6 changes: 0 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,6 @@ roslint_cpp()
###################################
## catkin specific configuration ##
###################################
# Generate messages in the 'msg' folder
add_message_files(
DIRECTORY msg
FILES
ImuBiasValidity.msg
)

add_service_files(
FILES
Expand Down
1 change: 0 additions & 1 deletion include/robot_localization/ros_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

#include <robot_localization/SetPose.h>
#include <robot_localization/ToggleFilterProcessing.h>
#include <robot_localization/ImuBiasValidity.h>

#include <ros/ros.h>
#include <std_msgs/Float64.h>
Expand Down
3 changes: 0 additions & 3 deletions msg/ImuBiasValidity.msg

This file was deleted.

18 changes: 12 additions & 6 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1905,7 +1905,9 @@ namespace RobotLocalization
boost::bind(&RosFilter<T>::imuMagnetometerValidityCallback, this, _1,
dynamic_correction_topic), ros::VoidPtr(),
ros::TransportHints().tcpNoDelay(nodelayImu)));
imuDataValidityPubMap_[dynamic_correction_topic] = nhLocal_.advertise<robot_localization::ImuBiasValidity>(dynamic_correction_topic+"/bias_estimator_validity", 20);
imuDataValidityPubMap_[dynamic_correction_topic + "_roll"] = nhLocal_.advertise<std_msgs::Bool>(dynamic_correction_topic + "/bias_estimator_validity_roll", 20);
imuDataValidityPubMap_[dynamic_correction_topic + "_pitch"] = nhLocal_.advertise<std_msgs::Bool>(dynamic_correction_topic + "/bias_estimator_validity_pitch", 20);
imuDataValidityPubMap_[dynamic_correction_topic + "_yaw"] = nhLocal_.advertise<std_msgs::Bool>(dynamic_correction_topic + "/bias_estimator_validity_yaw", 20);

// Subscribe to resets as well
topicSubs_.push_back(
Expand Down Expand Up @@ -3494,11 +3496,15 @@ namespace RobotLocalization
}

// publish validity of axis based on whether bias estimator updated the bias
robot_localization::ImuBiasValidity estimator_validity_msg;
estimator_validity_msg.roll = is_bias_valid[0];
estimator_validity_msg.pitch = is_bias_valid[1];
estimator_validity_msg.yaw = is_bias_valid[2];
imuDataValidityPubMap_[topicName].publish(estimator_validity_msg);
std_msgs::Bool estimator_validity_msg;
estimator_validity_msg.data = is_bias_valid[0];
imuDataValidityPubMap_[topicName + "_roll"].publish(estimator_validity_msg);

estimator_validity_msg.data = is_bias_valid[1];
imuDataValidityPubMap_[topicName + "_pitch"].publish(estimator_validity_msg);

estimator_validity_msg.data = is_bias_valid[2];
imuDataValidityPubMap_[topicName + "_yaw"].publish(estimator_validity_msg);

if(can_update == true)
{
Expand Down

0 comments on commit 3687999

Please sign in to comment.