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

Fix/gps throttle message #51

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion src/lib/xbot_positioning
1 change: 1 addition & 0 deletions src/mower_logic/cfg/MowerLogic.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -29,5 +29,6 @@ gen.add("add_fake_obstacle", bool_t, 0, "True to add a fake obstacle to hopefull
gen.add("ignore_gps_errors", bool_t, 0, "True to ignore gps errors. USE ONLY FOR SIMULATION!", False)
gen.add("max_first_point_attempts", int_t, 0, "Maximum attempts to reach the first point of the mow path before trimming", 3, 1, 10)
gen.add("max_first_point_trim_attempts", int_t, 0, "After <max_first_point_attempts> we start to trim the path beginning this often", 3, 1, 10)
gen.add("gps_message_throttle", int_t, 0, "throttle value for gps messages", 60, 1, 10000)

exit(gen.generate("mower_logic", "mower_logic", "MowerLogic"))
4 changes: 2 additions & 2 deletions src/mower_logic/src/mower_logic/mower_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -434,15 +434,15 @@ void checkSafety(const ros::TimerEvent &timer_event) {
// set this if we don't even have an orientation
high_level_status.gps_quality_percent = -1;
}
ROS_WARN_STREAM_THROTTLE(1,"Low quality GPS");
ROS_WARN_STREAM_THROTTLE(last_config.gps_message_throttle,"Low quality GPS");
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could leave it as it but just not log it when !currentBehavior->needs_gps())?

}

bool gpsTimeout = ros::Time::now() - last_good_gps > ros::Duration(last_config.gps_timeout);

if(gpsTimeout) {
// GPS = bad, set quality to 0
high_level_status.gps_quality_percent = 0;
ROS_WARN_STREAM_THROTTLE(1,"GPS timeout");
ROS_WARN_STREAM_THROTTLE(last_config.gps_message_throttle,"GPS timeout");
}

if (currentBehavior != nullptr && currentBehavior->needs_gps()) {
Expand Down
1 change: 1 addition & 0 deletions src/open_mower/launch/include/_localization.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<param name="max_gps_accuracy" value="0.2"/>
<param name="antenna_offset_x" value="$(env OM_ANTENNA_OFFSET_X)"/>
<param name="antenna_offset_y" value="$(env OM_ANTENNA_OFFSET_Y)"/>
<param name="gps_message_throttle" value="$(optenv OM_GPS_MESSAGE_THROTTLE 60)"/>
</node>
</group>
<group if="$(arg use_legacy_localization)">
Expand Down
1 change: 1 addition & 0 deletions src/open_mower/launch/open_mower.launch
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<param name="mow_angle_offset" value="$(optenv OM_MOWING_ANGLE_OFFSET 0)"/>
<param name="mow_angle_offset_is_absolute" value="$(optenv OM_MOWING_ANGLE_OFFSET_IS_ABSOLUTE False)"/>
<param name="mow_angle_increment" value="$(optenv OM_MOWING_ANGLE_INCREMENT 0)"/>
<param name="gps_message_throttle" value="$(optenv OM_GPS_MESSAGE_THROTTLE 60)"/>
<param name="battery_full_voltage" value="$(env OM_BATTERY_FULL_VOLTAGE)"/>
<param name="motor_hot_temperature" value="$(env OM_MOWING_MOTOR_TEMP_HIGH)"/>
<param name="motor_cold_temperature" value="$(env OM_MOWING_MOTOR_TEMP_LOW)"/>
Expand Down
5 changes: 3 additions & 2 deletions src/open_mower/launch/test_playback.launch
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,10 @@
<param name="max_gps_accuracy" value="0.2"/>
<param name="max_gps_accuracy" value="0.2"/>
<param name="skip_gyro_calibration" value="true"/>
<param name="gps_message_throttle" value="$(optenv OM_GPS_MESSAGE_THROTTLE 1)"/>
<param name="gyro_offset" value="0.01" />
<param name="antenna_offset_x" value="$(env OM_ANTENNA_OFFSET_X)"/>
<param name="antenna_offset_y" value="$(env OM_ANTENNA_OFFSET_Y)"/>
<param name="antenna_offset_x" value="$(env OM_ANTENNA_OFFSET_X)"/>
<param name="antenna_offset_y" value="$(env OM_ANTENNA_OFFSET_Y)"/>
</node>

<node pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" if="$(arg rqt_reconfigure)"/>
Expand Down