Skip to content

Commit

Permalink
removed aloam estimator (will be available as plugin in mrs_aloam_core
Browse files Browse the repository at this point in the history
metapackage)
  • Loading branch information
petrlmat committed Oct 25, 2023
1 parent f9e0eac commit 9fe7908
Show file tree
Hide file tree
Showing 8 changed files with 4 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@ mrs_uav_managers:
address: "mrs_uav_state_estimators/Rtk"
rtk_garmin:
address: "mrs_uav_state_estimators/RtkGarmin"
aloam:
address: "mrs_uav_state_estimators/Aloam"
vio:
address: "mrs_uav_state_estimators/Vio"
hector_garmin:
Expand Down
3 changes: 1 addition & 2 deletions config/public/active_estimators.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,11 @@ mrs_uav_managers:
estimation_manager:

# loaded state estimator plugins
# available in mrs_uav_state_estimators: gps_garmin, gps_baro, rtk, aloam, ground_truth, dummy
# available in mrs_uav_state_estimators: gps_garmin, gps_baro, rtk, ground_truth, dummy
state_estimators: [
"gps_garmin",
"gps_baro",
# "rtk",
# "aloam",
# "ground_truth",
# "dummy"
]
Expand Down
3 changes: 0 additions & 3 deletions config/public/constraint_manager/constraint_manager.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ mrs_uav_managers:
"gps_baro",
"rtk",
"rtk_garmin",
"aloam",
"hector_garmin",
"vio",
"optflow",
Expand All @@ -28,7 +27,6 @@ mrs_uav_managers:
gps_baro: ["slow", "medium", "fast"]
rtk: ["slow", "medium", "fast"]
rtk_garmin: ["slow", "medium", "fast"]
aloam: ["slow"]
hector_garmin: ["slow"]
vio: ["slow"]
optflow: ["slow"]
Expand All @@ -43,7 +41,6 @@ mrs_uav_managers:
gps_baro: "slow"
rtk: "slow"
rtk_garmin: "slow"
aloam: "slow"
hector_garmin: "slow"
vio: "slow"
optflow: "slow"
Expand Down
3 changes: 0 additions & 3 deletions config/public/gain_manager/gain_manager.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ mrs_uav_managers:
"gps_baro",
"rtk",
"rtk_garmin",
"aloam",
"hector_garmin",
"vio",
"optflow",
Expand All @@ -27,7 +26,6 @@ mrs_uav_managers:
gps_baro: ["supersoft", "soft"]
rtk: ["supersoft", "soft"]
rtk_garmin: ["supersoft", "soft"]
aloam: ["supersoft", "soft"]
hector_garmin: ["supersoft", "soft"]
vio: ["supersoft", "soft"]
optflow: ["supersoft", "soft"]
Expand All @@ -42,7 +40,6 @@ mrs_uav_managers:
gps_baro: "soft"
rtk: "soft"
rtk_garmin: "soft"
aloam: "supersoft"
hector_garmin: "supersoft"
vio: "supersoft"
optflow: "supersoft"
Expand Down
22 changes: 0 additions & 22 deletions config/public/transform_manager/transform_manager.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -32,18 +32,6 @@ mrs_uav_managers:
parent: "fcu" # fcu should be the parent if using the default inverted mrs tf tree convention with fcu as the root of the tf tree
child: "fcu_untilted"

mapping_origin_tf:
enabled: true
debug_prints: false
lateral_topic: "slam/odom" # name of the topic used for x, y components of the tf (expects nav_msgs/Odometry topic type)
altitude_topic: "slam/odom" # name of the topic used for z components of the tf (expects nav_msgs/Odometry topic type)
orientation_topic: "hw_api/orientation" # name of the topic used for orientation components of the tf (expects geometry_msgs/Quaternion topic type)
inverted: true # publish as inverted tf (the default for inverted mrs tf tree convention)
custom_frame_id:
enabled: true
frame_id: "mapping_origin"


# the list of additional source topics from which the tfs will be constructed
tf_sources: []

Expand Down Expand Up @@ -101,16 +89,6 @@ mrs_uav_managers:
inverted: true # publish as inverted tf (the default for inverted mrs tf tree convention)
republish_in_frames: [] # the odometry message will be transformed and republished in the specified frames

aloam:
odom_topic: "odom" # name of the topic (expects nav_msgs/Odometry topic type)
tf_from_attitude: # used for transforming velocities before full transform is available
enabled: true
attitude_topic: "attitude" # name of the attitude topic(expects geometry_msgs/QuaternionStamped topic type)
namespace: "estimation_manager/aloam" # the namespace of the topic (usually the node that publishes the topic)
utm_based: false # if true, will publish tf to utm_origin
inverted: true # publish as inverted tf (the default for inverted mrs tf tree convention)
republish_in_frames: [] # the odometry message will be transformed and republished in the specified frames

hector_garmin:
odom_topic: "odom" # name of the topic (expects nav_msgs/Odometry topic type)
tf_from_attitude: # used for transforming velocities before full transform is available
Expand Down
2 changes: 1 addition & 1 deletion include/transform_manager/tf_mapping_origin.h
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class TfMappingOrigin {

const double hdg_mapping_old = mrs_lib::AttitudeConverter(msg->pose.pose.orientation).getHeading();

/* publish aloam mapping origin tf //{ */
/* publish mapping origin tf //{ */

bool clear_needed = false;

Expand Down
2 changes: 1 addition & 1 deletion launch/estimation_manager.launch
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
<!-- Load the default param files -->
<param name="private_config" value="$(find mrs_uav_managers)/config/private/estimation_manager/estimation_manager.yaml" />
<param name="public_config" value="$(find mrs_uav_managers)/config/public/estimation_manager/estimation_manager.yaml" />
<param name="estimators_config" value="$(find mrs_uav_managers)/config/public/estimators.yaml" />
<param name="estimators_config" value="$(find mrs_uav_managers)/config/private/estimators.yaml" />
<param name="active_estimators_config" value="$(find mrs_uav_managers)/config/public/active_estimators.yaml" />

<param if="$(eval arg('platform_config') == '')" name="platform_config" value="" />
Expand Down
2 changes: 1 addition & 1 deletion src/transform_manager/transform_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ void TransformManager::onInit() {

// initialize mapping_origin tf
bool mapping_origin_tf_enabled;
param_loader.loadParam(yaml_prefix + "mapping_origin_tf/enabled", mapping_origin_tf_enabled);
param_loader.loadParam(yaml_prefix + "mapping_origin_tf/enabled", mapping_origin_tf_enabled, false);

if (mapping_origin_tf_enabled) {

Expand Down

0 comments on commit 9fe7908

Please sign in to comment.