Skip to content

Commit

Permalink
Removing UAV_MASS from launch files, will be handeled by Control Manager
Browse files Browse the repository at this point in the history
  • Loading branch information
DanHert committed Feb 27, 2024
1 parent aba455c commit 055cca3
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 13 deletions.
8 changes: 0 additions & 8 deletions launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
<arg name="UAV_NAME" default="$(optenv UAV_NAME)"/>
<arg name="NATO_NAME" default="$(optenv NATO_NAME)"/>
<arg name="UAV_TYPE" default="$(optenv UAV_TYPE)"/>
<arg name="UAV_MASS" default="$(optenv UAV_MASS)"/>
<arg name="SENSORS" default="$(optenv SENSORS)"/>
<arg name="RUN_TYPE" default="$(optenv RUN_TYPE)"/>
<arg name="PIXGARM" default="$(optenv PIXGARM false)"/>
Expand All @@ -18,8 +17,6 @@

<arg name="config_file" default=""/>

<arg if="$(eval arg('RUN_TYPE') == 'realworld')" name="UAV_MASS" default="$(arg UAV_MASS)" />

<group ns="$(arg UAV_NAME)">

<node name="mrs_uav_status_acquisition" pkg="mrs_uav_status" type="data_acquisition" output="screen" respawn="true" launch-prefix="$(arg launch_prefix)">
Expand All @@ -31,11 +28,6 @@
<param name="sensors" value="$(arg SENSORS)" />
<param name="pixgarm" type="bool" value="$(arg PIXGARM)" />

<param if="$(eval arg('RUN_TYPE') == 'realworld')" name="uav_mass" value="$(arg UAV_MASS)" />

<!-- TODO this needs to be somehow obtained from the control manager -->
<param if="$(eval arg('RUN_TYPE') == 'simulation')" name="uav_mass" value="1.0" />

<rosparam file="$(find mrs_uav_status)/config/default.yaml" command="load" />
<rosparam if="$(eval not arg('config_file') == '')" file="$(arg config_file)" />

Expand Down
3 changes: 0 additions & 3 deletions launch/terminal.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@

<arg name="config_file" default=""/>

<arg if="$(eval arg('RUN_TYPE') == 'realworld')" name="UAV_MASS" default="$(env UAV_MASS)" />

<group ns="$(arg UAV_NAME)">

<node name="mrs_uav_status" pkg="mrs_uav_status" type="mrs_uav_status" output="screen" respawn="false" launch-prefix="$(arg launch_prefix)">
Expand All @@ -27,7 +25,6 @@
<param name="pwd" value="$(arg PWD)" />
<param name="nato_name" value="$(arg NATO_NAME)" />
<param name="uav_type" value="$(arg UAV_TYPE)" />
<param if="$(eval arg('RUN_TYPE') == 'realworld')" name="uav_mass" value="$(arg UAV_MASS)" />
<param name="run_type" value="$(arg RUN_TYPE)" />
<param name="sensors" value="$(arg SENSORS)" />
<param name="pixgarm" type="bool" value="$(arg PIXGARM)" />
Expand Down
2 changes: 0 additions & 2 deletions src/data_acquisition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,8 +269,6 @@ Acquisition::Acquisition() {

mrs_lib::ParamLoader param_loader(nh_, "Acquisition");

string tmp_uav_mass;

param_loader.loadParam("uav_name", _uav_name_);
param_loader.loadParam("uav_type", _uav_type_);
param_loader.loadParam("run_type", _run_type_);
Expand Down

0 comments on commit 055cca3

Please sign in to comment.