Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Set twist_marker/use_stamped to default true, to match twist_mux #55

Merged
merged 2 commits into from
Jan 3, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/twist_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,12 +108,12 @@ class TwistMarkerPublisher : public rclcpp::Node
{
std::string frame_id;
double scale;
bool use_stamped;
bool use_stamped = true;
double z;

this->declare_parameter("frame_id", "base_footprint");
this->declare_parameter("scale", 1.0);
this->declare_parameter("use_stamped", false);
this->declare_parameter("use_stamped", true);
this->declare_parameter("vertical_position", 2.0);

this->get_parameter<std::string>("frame_id", frame_id);
Expand Down
4 changes: 3 additions & 1 deletion src/twist_mux.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,9 @@ TwistMux::TwistMux()
void TwistMux::init()
{
// Get use stamped parameter
bool use_stamped;
bool use_stamped = true;
this->declare_parameter("use_stamped", use_stamped);

auto nh = std::shared_ptr<rclcpp::Node>(this, [](rclcpp::Node *) {});
fetch_param(nh, "use_stamped", use_stamped);

Expand Down
Loading