Skip to content

Commit fdba632

Browse files
authored
altitude logic (#53)
1 parent 6123c8f commit fdba632

4 files changed

Lines changed: 28 additions & 3 deletions

File tree

vortex_utils/include/vortex/utils/types.hpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -448,8 +448,9 @@ enum class WaypointMode : uint8_t {
448448
FORWARD_HEADING = 2, ///< Control x, y, z with yaw toward target.
449449
ONLY_ORIENTATION = 3, ///< Control roll, pitch, yaw; hold current position.
450450
POSITION_AND_YAW = 4, ///< Control x, y, z and yaw; force roll=pitch=0.
451-
XY_AND_YAW = 5, ///< Control x, y and yaw; hold z, force roll=pitch=0.
452-
XY_FORWARD_DIR = 6, ///< Control x, y; hold z; yaw auto-computed toward target.
451+
XY_AND_YAW = 5, ///< Control x, y and yaw; hold z, force roll=pitch=0.
452+
XY_FORWARD_DIR =
453+
6, ///< Control x, y; hold z; yaw auto-computed toward target.
453454
};
454455

455456
/**
@@ -458,6 +459,8 @@ enum class WaypointMode : uint8_t {
458459
struct Waypoint {
459460
Pose pose{};
460461
WaypointMode mode = WaypointMode::FULL_POSE;
462+
bool keep_altitude{false};
463+
double desired_altitude{0.0};
461464
};
462465

463466
struct SonarInfo {

vortex_utils/include/vortex/utils/waypoint_utils.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@ struct WaypointGoal {
1717
Pose pose;
1818
WaypointMode mode;
1919
double convergence_threshold{0.1};
20+
bool keep_altitude{false};
21+
double desired_altitude{0.0};
2022
};
2123

2224
/**
@@ -123,6 +125,8 @@ Pose load_pose_from_yaml(const std::string& file_path,
123125
* ONLY_POSITION, FORWARD_HEADING x: 1.0 y: 0.0 z: -0.5 orientation: #
124126
* Required for FULL_POSE, ONLY_ORIENTATION roll: 0.0 pitch: 0.0 yaw: 3.14159
125127
* convergence_threshold: 0.1 # Optional, default is 0.1
128+
* keep_altitude: true # Optional, default false
129+
* desired_altitude: 1.5 # Required when keep_altitude is true
126130
* @endcode
127131
*
128132
* @param file_path Path to the YAML file.

vortex_utils/src/waypoint_utils.cpp

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -269,9 +269,25 @@ WaypointGoal load_waypoint_goal_from_yaml(const std::string& file_path,
269269
convergence_threshold = wp["convergence_threshold"].as<double>();
270270
}
271271

272+
bool keep_altitude = false;
273+
double desired_altitude = 0.0;
274+
if (wp["keep_altitude"]) {
275+
keep_altitude = wp["keep_altitude"].as<bool>();
276+
}
277+
if (keep_altitude) {
278+
if (!wp["desired_altitude"]) {
279+
throw std::runtime_error("Waypoint '" + identifier +
280+
"' has keep_altitude=true but is missing "
281+
"required field 'desired_altitude'");
282+
}
283+
desired_altitude = wp["desired_altitude"].as<double>();
284+
}
285+
272286
return WaypointGoal{.pose = pose,
273287
.mode = mode,
274-
.convergence_threshold = convergence_threshold};
288+
.convergence_threshold = convergence_threshold,
289+
.keep_altitude = keep_altitude,
290+
.desired_altitude = desired_altitude};
275291
}
276292

277293
LandmarkConvergenceGoal load_landmark_goal_from_yaml(

vortex_utils_ros/include/vortex/utils/ros/waypoint_ros_conversions.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,8 @@ inline vortex::utils::types::Waypoint waypoint_from_ros(
7777
vortex::utils::types::Waypoint wp;
7878
wp.pose = vortex::utils::ros_conversions::ros_pose_to_pose(ros_wp.pose);
7979
wp.mode = waypoint_mode_from_ros(ros_wp.waypoint_mode);
80+
wp.keep_altitude = ros_wp.keep_altitude;
81+
wp.desired_altitude = ros_wp.desired_altitude;
8082
return wp;
8183
}
8284

0 commit comments

Comments
 (0)