Skip to content

Commit

Permalink
Merge pull request #192 from enwaytech/av/remove_launchers
Browse files Browse the repository at this point in the history
Increase max stddev, add pose visualization, fix error messages
  • Loading branch information
mintar committed Dec 20, 2023
2 parents 77aaa91 + 25f310d commit 13ff13a
Show file tree
Hide file tree
Showing 3 changed files with 48 additions and 7 deletions.
2 changes: 1 addition & 1 deletion imu_filter_madgwick/cfg/ImuFilterMadgwick.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,6 @@ gen.add("zeta", double_t, 0, "Gyro drift gain (approx. rad/s).", 0, -1.0, 1.0)
gen.add("mag_bias_x", double_t, 0, "Magnetometer bias (hard iron correction), x component.", 0, -10.0, 10.0)
gen.add("mag_bias_y", double_t, 0, "Magnetometer bias (hard iron correction), y component.", 0, -10.0, 10.0)
gen.add("mag_bias_z", double_t, 0, "Magnetometer bias (hard iron correction), z component.", 0, -10.0, 10.0)
gen.add("orientation_stddev", double_t, 0, "Standard deviation of the orientation estimate.", 0, 0, 1.0)
gen.add("orientation_stddev", double_t, 0, "Standard deviation of the orientation estimate.", 0, 0, 100.0)

exit(gen.generate(PACKAGE, "dynamic_reconfigure_node", "ImuFilterMadgwick"))
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,9 @@
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/MagneticField.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <tf2_ros/buffer.h>
#include "tf2_ros/transform_broadcaster.h"
#include <tf2_ros/transform_listener.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
Expand Down Expand Up @@ -74,8 +76,11 @@ class ImuFilterRos

ros::Publisher rpy_filtered_debug_publisher_;
ros::Publisher rpy_raw_debug_publisher_;
ros::Publisher orientation_filtered_publisher_;
ros::Publisher imu_publisher_;
tf2_ros::TransformBroadcaster tf_broadcaster_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

boost::shared_ptr<FilterConfigServer> config_server_;
ros::Timer check_topics_timer_;
Expand Down Expand Up @@ -111,6 +116,7 @@ class ImuFilterRos
void imuCallback(const ImuMsg::ConstPtr& imu_msg_raw);

void publishFilteredMsg(const ImuMsg::ConstPtr& imu_msg_raw);
void publishOrientationFiltered(const ImuMsg::ConstPtr& imu_msg);
void publishTransform(const ImuMsg::ConstPtr& imu_msg_raw);

void publishRawMsg(const ros::Time& t, float roll, float pitch, float yaw);
Expand Down
47 changes: 41 additions & 6 deletions imu_filter_madgwick/src/imu_filter_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,15 @@
#include "imu_filter_madgwick/imu_filter_ros.h"
#include "imu_filter_madgwick/stateless_orientation.h"
#include "geometry_msgs/TransformStamped.h"
#include "geometry_msgs/PoseStamped.h"
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Matrix3x3.h>

ImuFilterRos::ImuFilterRos(ros::NodeHandle nh, ros::NodeHandle nh_private)
: nh_(nh), nh_private_(nh_private), initialized_(false)
: nh_(nh),
nh_private_(nh_private),
initialized_(false),
tf_listener_(tf_buffer_)
{
ROS_INFO("Starting ImuFilter");

Expand Down Expand Up @@ -121,6 +125,10 @@ ImuFilterRos::ImuFilterRos(ros::NodeHandle nh, ros::NodeHandle nh_private)

rpy_raw_debug_publisher_ = nh_.advertise<geometry_msgs::Vector3Stamped>(
ros::names::resolve("imu") + "/rpy/raw", 5);

orientation_filtered_publisher_ =
nh_private.advertise<geometry_msgs::PoseStamped>(
ros::names::resolve("imu") + "/orientation_filtered", 5);
}

// **** register subscribers
Expand Down Expand Up @@ -407,9 +415,38 @@ void ImuFilterRos::publishFilteredMsg(const ImuMsg::ConstPtr& imu_msg_raw)

rpy.header = imu_msg_raw->header;
rpy_filtered_debug_publisher_.publish(rpy);

publishOrientationFiltered(imu_msg);
}
}

void ImuFilterRos::publishOrientationFiltered(const ImuMsg::ConstPtr& imu_msg)
{
geometry_msgs::PoseStamped pose_msg;
pose_msg.header.stamp = imu_msg->header.stamp;
pose_msg.header.frame_id = fixed_frame_;
pose_msg.pose.orientation = imu_msg->orientation;

// get the current transform from the fixed frame to the imu frame
geometry_msgs::TransformStamped transform;
try
{
transform = tf_buffer_.lookupTransform(
fixed_frame_, imu_msg->header.frame_id, imu_msg->header.stamp,
ros::Duration(0.1));
} catch (tf2::TransformException& ex)
{
ROS_WARN("%s", ex.what());
return;
}

pose_msg.pose.position.x = transform.transform.translation.x;
pose_msg.pose.position.y = transform.transform.translation.y;
pose_msg.pose.position.z = transform.transform.translation.z;

orientation_filtered_publisher_.publish(pose_msg);
}

void ImuFilterRos::publishRawMsg(const ros::Time& t, float roll, float pitch,
float yaw)
{
Expand Down Expand Up @@ -445,13 +482,11 @@ void ImuFilterRos::checkTopicsTimerCallback(const ros::TimerEvent&)
{
if (use_mag_)
ROS_WARN_STREAM("Still waiting for data on topics "
<< ros::names::resolve("imu") << "/data_raw"
<< " and " << ros::names::resolve("imu") << "/mag"
<< "...");
<< imu_subscriber_->getTopic() << " and "
<< mag_subscriber_->getTopic() << "...");
else
ROS_WARN_STREAM("Still waiting for data on topic "
<< ros::names::resolve("imu") << "/data_raw"
<< "...");
<< imu_subscriber_->getTopic() << "...");
}

void ImuFilterRos::reset()
Expand Down

0 comments on commit 13ff13a

Please sign in to comment.