Skip to content

Commit

Permalink
plugins: Fix misprint
Browse files Browse the repository at this point in the history
Fix #1709

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>
  • Loading branch information
vooon committed Feb 16, 2022
1 parent a32232d commit c035b8f
Show file tree
Hide file tree
Showing 27 changed files with 121 additions and 121 deletions.
4 changes: 2 additions & 2 deletions mavros/include/mavros/plugin.hpp
Expand Up @@ -218,7 +218,7 @@ class Plugin : public std::enable_shared_from_this<Plugin>
* Adds parameter to watch and declares it
*/
template<typename ParameterT>
auto node_declate_and_watch_parameter(
auto node_declare_and_watch_parameter(
const std::string & name, ParameterFunctorT cb,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
Expand All @@ -239,7 +239,7 @@ class Plugin : public std::enable_shared_from_this<Plugin>
}

template<typename ParameterT>
auto node_declate_and_watch_parameter(
auto node_declare_and_watch_parameter(
const std::string & name, const ParameterT & default_value,
ParameterFunctorT cb,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/altitude.cpp
Expand Up @@ -41,7 +41,7 @@ class AltitudePlugin : public plugin::Plugin
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"frame_id", "map", [&](const rclcpp::Parameter & p) {
frame_id = p.as_string();
});
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/command.cpp
Expand Up @@ -73,12 +73,12 @@ class CommandPlugin : public plugin::Plugin
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"command_ack_timeout", command_ack_timeout_dt.seconds(), [&](const rclcpp::Parameter & p) {
command_ack_timeout_dt = rclcpp::Duration::from_seconds(p.as_double());
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_comp_id_system_control", false, [&](const rclcpp::Parameter & p) {
use_comp_id_system_control = p.as_bool();
});
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/geofence.cpp
Expand Up @@ -37,12 +37,12 @@ class GeofencePlugin : public plugin::MissionBase
enable_node_watch_parameters();

// NOTE(vooon): I'm not quite sure that this option would work with mavros router
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"pull_after_gcs", true, [&](const rclcpp::Parameter & p) {
do_pull_after_gcs = p.as_bool();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_mission_item_int", true, [&](const rclcpp::Parameter & p) {
use_mission_item_int = p.as_bool();
});
Expand Down
18 changes: 9 additions & 9 deletions mavros/src/plugins/global_position.cpp
Expand Up @@ -66,42 +66,42 @@ class GlobalPositionPlugin : public plugin::Plugin
enable_node_watch_parameters();

// general params
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"frame_id", "map", [&](const rclcpp::Parameter & p) {
frame_id = p.as_string();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
child_frame_id = p.as_string();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"rot_covariance", 99999.0, [&](const rclcpp::Parameter & p) {
rot_cov = p.as_double();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"gps_uere", 1.0, [&](const rclcpp::Parameter & p) {
gps_uere = p.as_double();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_relative_alt", true, [&](const rclcpp::Parameter & p) {
use_relative_alt = p.as_bool();
});

// tf subsection
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.send", false, [&](const rclcpp::Parameter & p) {
tf_send = p.as_bool();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.frame_id", "map", [&](const rclcpp::Parameter & p) {
tf_frame_id = p.as_string();
});
// The global_origin should be represented as "earth" coordinate frame (ECEF) (REP 105)
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.global_frame_id", "earth", [&](const rclcpp::Parameter & p) {
tf_global_frame_id = p.as_string();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
tf_child_frame_id = p.as_string();
});
Expand Down
10 changes: 5 additions & 5 deletions mavros/src/plugins/imu.cpp
Expand Up @@ -79,27 +79,27 @@ class IMUPlugin : public plugin::Plugin
* transformation from the ENU frame to the base_link frame (ENU <-> base_link).
* THIS ORIENTATION IS NOT THE SAME AS THAT REPORTED BY THE FCU (NED <-> aircraft).
*/
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"frame_id", "base_link", [&](const rclcpp::Parameter & p) {
frame_id = p.as_string();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"linear_acceleration_stdev", 0.0003, [&](const rclcpp::Parameter & p) {
auto linear_stdev = p.as_double();
setup_covariance(linear_acceleration_cov, linear_stdev);
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"angular_velocity_stdev", 0.02 * (M_PI / 180.0), [&](const rclcpp::Parameter & p) {
auto angular_stdev = p.as_double();
setup_covariance(angular_velocity_cov, angular_stdev);
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"orientation_stdev", 1.0, [&](const rclcpp::Parameter & p) {
auto orientation_stdev = p.as_double();
setup_covariance(orientation_cov, orientation_stdev);
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"magnetic_stdev", 0.0, [&](const rclcpp::Parameter & p) {
auto mag_stdev = p.as_double();
setup_covariance(magnetic_cov, mag_stdev);
Expand Down
8 changes: 4 additions & 4 deletions mavros/src/plugins/local_position.cpp
Expand Up @@ -59,22 +59,22 @@ class LocalPositionPlugin : public plugin::Plugin

// header frame_id.
// default to map (world-fixed, ENU as per REP-105).
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"frame_id", "map", [&](const rclcpp::Parameter & p) {
frame_id = p.as_string();
});

// Important tf subsection
// Report the transform from world to base_link here.
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.send", false, [&](const rclcpp::Parameter & p) {
tf_send = p.as_bool();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.frame_id", "map", [&](const rclcpp::Parameter & p) {
tf_frame_id = p.as_string();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"tf.child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
tf_child_frame_id = p.as_string();
});
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/rallypoint.cpp
Expand Up @@ -36,12 +36,12 @@ class RallypointPlugin : public plugin::MissionBase
enable_node_watch_parameters();

// NOTE(vooon): I'm not quite sure that this option would work with mavros router
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"pull_after_gcs", true, [&](const rclcpp::Parameter & p) {
do_pull_after_gcs = p.as_bool();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_mission_item_int", true, [&](const rclcpp::Parameter & p) {
use_mission_item_int = p.as_bool();
});
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/setpoint_attitude.cpp
Expand Up @@ -64,12 +64,12 @@ class SetpointAttitudePlugin : public plugin::Plugin,

auto qos = rclcpp::QoS(10);

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"reverse_thrust", false, [&](const rclcpp::Parameter & p) {
reverse_thrust = p.as_bool();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_quaternion", false, [&](const rclcpp::Parameter & p) {
auto use_quaternion = p.as_bool();

Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_position.cpp
Expand Up @@ -52,7 +52,7 @@ class SetpointPositionPlugin : public plugin::Plugin,
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"mav_frame", "LOCAL_NED", [&](const rclcpp::Parameter & p) {
auto mav_frame_str = p.as_string();
auto new_mav_frame = utils::mav_frame_from_str(mav_frame_str);
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_raw.cpp
Expand Up @@ -53,7 +53,7 @@ class SetpointRawPlugin : public plugin::Plugin,
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"thrust_scaling", NAN, [&](const rclcpp::Parameter & p) {
thrust_scaling = p.as_double();
});
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/setpoint_trajectory.cpp
Expand Up @@ -55,12 +55,12 @@ class SetpointTrajectoryPlugin : public plugin::Plugin,
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"frame_id", "map", [&](const rclcpp::Parameter & p) {
frame_id = p.as_string();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"mav_frame", "LOCAL_NED", [&](const rclcpp::Parameter & p) {
auto mav_frame_str = p.as_string();
auto new_mav_frame = utils::mav_frame_from_str(mav_frame_str);
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_velocity.cpp
Expand Up @@ -49,7 +49,7 @@ class SetpointVelocityPlugin : public plugin::Plugin,
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"mav_frame", "LOCAL_NED", [&](const rclcpp::Parameter & p) {
auto mav_frame_str = p.as_string();
auto new_mav_frame = utils::mav_frame_from_str(mav_frame_str);
Expand Down
10 changes: 5 additions & 5 deletions mavros/src/plugins/sys_status.cpp
Expand Up @@ -428,7 +428,7 @@ class SystemStatusPlugin : public plugin::Plugin
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"conn_timeout", 10.0, [&](const rclcpp::Parameter & p) {
auto conn_timeout = rclcpp::Duration::from_seconds(p.as_double());

Expand All @@ -438,14 +438,14 @@ class SystemStatusPlugin : public plugin::Plugin
std::bind(&SystemStatusPlugin::timeout_cb, this));
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"min_voltage", 10.0, [&](const rclcpp::Parameter & p) {
auto min_voltage = p.as_double();

batt_diag.set_min_voltage(min_voltage);
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"disable_diag", false, [&](const rclcpp::Parameter & p) {
disable_diag = p.as_bool();

Expand All @@ -460,13 +460,13 @@ class SystemStatusPlugin : public plugin::Plugin
}
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"heartbeat_mav_type", utils::enum_to_name(
conn_heartbeat_mav_type), [&](const rclcpp::Parameter & p) {
conn_heartbeat_mav_type = utils::mav_type_from_str(p.as_string());
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"heartbeat_rate", 1.0, [&](const rclcpp::Parameter & p) {
auto rate_d = p.as_double();

Expand Down
26 changes: 13 additions & 13 deletions mavros/src/plugins/sys_time.cpp
Expand Up @@ -160,19 +160,19 @@ class SystemTimePlugin : public plugin::Plugin
{
enable_node_watch_parameters();

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"time_ref_source", "fcu", [&](const rclcpp::Parameter & p) {
time_ref_source = p.as_string();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_mode", "MAVLINK", [&](const rclcpp::Parameter & p) {
auto ts_mode = utils::timesync_mode_from_str(p.as_string());
uas->set_timesync_mode(ts_mode);
RCLCPP_INFO_STREAM(get_logger(), "TM: Timesync mode: " << utils::to_string(ts_mode));
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"system_time_rate", 0.0, [&](const rclcpp::Parameter & p) {
auto rate_d = p.as_double();

Expand All @@ -191,7 +191,7 @@ class SystemTimePlugin : public plugin::Plugin
}
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_rate", 0.0, [&](const rclcpp::Parameter & p) {
auto rate_d = p.as_double();

Expand Down Expand Up @@ -223,22 +223,22 @@ class SystemTimePlugin : public plugin::Plugin
// tighter estimation of the skew (derivative), but will negatively affect how fast the
// filter reacts to clock skewing (e.g cause by temperature changes to the oscillator).
// Larger values will cause large-amplitude oscillations.
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_alpha_initial", 0.05, [&](const rclcpp::Parameter & p) {
filter_alpha_initial = p.as_double();
reset_filter();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_beta_initial", 0.05, [&](const rclcpp::Parameter & p) {
filter_beta_initial = p.as_double();
reset_filter();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_alpha_final", 0.003, [&](const rclcpp::Parameter & p) {
filter_alpha_final = p.as_double();
reset_filter();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"timesync_beta_final", 0.003, [&](const rclcpp::Parameter & p) {
filter_beta_final = p.as_double();
reset_filter();
Expand All @@ -250,7 +250,7 @@ class SystemTimePlugin : public plugin::Plugin
// exhanged timesync packets is less than convergence_window. A lower value will
// allow the timesync to converge faster, but with potentially less accurate initial
// offset and skew estimates.
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"convergence_window", 500, [&](const rclcpp::Parameter & p) {
convergence_window = p.as_int();
});
Expand All @@ -264,19 +264,19 @@ class SystemTimePlugin : public plugin::Plugin
// estimate are not used to update the filter. More than max_consecutive_high_deviation number
// of such events in a row will reset the filter. This usually happens only due to a time jump
// on the remote system.
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"max_rtt_sample", 10, [&](const rclcpp::Parameter & p) {
max_rtt_sample = p.as_int(); // in ms
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"max_deviation_sample", 10, [&](const rclcpp::Parameter & p) {
max_deviation_sample = p.as_int(); // in ms
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"max_consecutive_high_rtt", 10, [&](const rclcpp::Parameter & p) {
max_cons_high_rtt = p.as_int();
});
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"max_consecutive_high_deviation", 10, [&](const rclcpp::Parameter & p) {
max_cons_high_deviation = p.as_int();
});
Expand Down
6 changes: 3 additions & 3 deletions mavros/src/plugins/waypoint.cpp
Expand Up @@ -45,17 +45,17 @@ class WaypointPlugin : public plugin::MissionBase
enable_node_watch_parameters();

// NOTE(vooon): I'm not quite sure that this option would work with mavros router
node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"pull_after_gcs", true, [&](const rclcpp::Parameter & p) {
do_pull_after_gcs = p.as_bool();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"use_mission_item_int", true, [&](const rclcpp::Parameter & p) {
use_mission_item_int = p.as_bool();
});

node_declate_and_watch_parameter(
node_declare_and_watch_parameter(
"enable_partial_push", 2, [&](const rclcpp::Parameter & p) {
RCLCPP_DEBUG_STREAM(get_logger(), log_prefix << ": enable_partial_push = " << p);

Expand Down

0 comments on commit c035b8f

Please sign in to comment.