Skip to content

Commit

Permalink
Topic names refactor and readme changes.
Browse files Browse the repository at this point in the history
  • Loading branch information
Fixit-Davide committed Jan 19, 2024
1 parent 4ed86e9 commit 6e1b824
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 11 deletions.
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ The cumulative error while stationary due to the movement of the Earth on the Ya
## Parametrization:
- topics:
- imu: Input topic for the IMU data. (sensor_msgs::msg::Imu)
- rover_status: Input topic for the system's status. (std_msgs::msg::Bool)
- input_status: Input topic for the system's status. (std_msgs::msg::Bool)
- filter_status: Output topic that publish the filter's state. (std_msgs::msg::Bool)
- output: output topic for the filtered measurements. (sensor_msgs::msg::Imu)
- zero_velocity_detection:
- seconds: time frame (in sec) which the algorithm will wait to establish if the stationary conditions are met. (double)
Expand Down
4 changes: 2 additions & 2 deletions include/imu_zupt/imu_zupt.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ class ImuZupt : public rclcpp::Node
std::string source_topic_imu;
std::string dest_topic;
std::string err_topic;
std::string status_topic;
std::string rover_status_topic;
std::string filter_status_topic;
std::string input_status_topic;
bool publish_status;
bool publish_err;
bool use_degree;
Expand Down
4 changes: 2 additions & 2 deletions params/params.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
imu_zupt:
ros__parameters:
topics:
locomotion: /locomotion/odom
imu: /imu/data
output: /imu/data_zupt
error: /imu/yaw_err
status: /imu_zupt/active
filter_status: /imu_zupt/active
input_status: /input_status
covariance:
override: true
value: 0.001
Expand Down
12 changes: 6 additions & 6 deletions src/imu_zupt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,33 +15,33 @@ ImuZupt::ImuZupt(const rclcpp::NodeOptions & options)
source_topic_imu = declare_parameter<std::string>("topics.imu", "/imu/data");
dest_topic = declare_parameter<std::string>("topics.output", "/imu/data_zupt");
err_topic = declare_parameter<std::string>("topics.error", "/imu/yaw_err");
status_topic =
declare_parameter<std::string>("topics.zero_velocity_detected", "/imu_zupt/active");
filter_status_topic =
declare_parameter<std::string>("topics.filter_status", "/imu_zupt/active");
publish_err = declare_parameter<bool>("error.publish", true);
use_degree = declare_parameter<bool>("error.in_degrees", true);
override_covariance = declare_parameter<bool>("covariance.override", true);
covariance = declare_parameter<double>("covariance.value", 0.001);
publish_status = declare_parameter<bool>("zero_velocity_detection.publish", true);
rover_status_topic = declare_parameter<std::string>("topics.rover_status", "/rover_status");
input_status_topic = declare_parameter<std::string>("topics.input_status", "/input_status");

rover_status_subs_ =
create_subscription<std_msgs::msg::Bool>(
rover_status_topic, 1,
input_status_topic, 1,
std::bind(&ImuZupt::status_callback, this, _1));
imu_subs_ =
create_subscription<sensor_msgs::msg::Imu>(
source_topic_imu, 1,
std::bind(&ImuZupt::imu_callback, this, _1));
zupt_publ_ = create_publisher<sensor_msgs::msg::Imu>(dest_topic, 1);
err_publ_ = create_publisher<std_msgs::msg::Float64>(err_topic, 1);
status_publ_ = create_publisher<std_msgs::msg::Bool>(status_topic, 1);
status_publ_ = create_publisher<std_msgs::msg::Bool>(filter_status_topic, 1);
}

void ImuZupt::imu_callback(const sensor_msgs::msg::Imu::SharedPtr imu_msg)
{
if (!active) {return;}
std::unique_ptr<sensor_msgs::msg::Imu> pkt_imu_zupt(new sensor_msgs::msg::Imu);
pkt_imu_zupt->header = imu_msg->header;
*pkt_imu_zupt = *imu_msg;

tf2::fromMsg(imu_msg->orientation, q1);
tf2::Matrix3x3 m(q1);
Expand Down

0 comments on commit 6e1b824

Please sign in to comment.