Skip to content

Commit bfe6e3e

Browse files
committed
made separate takeoff and landing velocities
1 parent d676ee5 commit bfe6e3e

File tree

4 files changed

+43
-46
lines changed

4 files changed

+43
-46
lines changed

robot/ros_ws/src/autonomy/3_local/b_planners/takeoff_landing_planner/config/takeoff_landing_planner.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,8 @@
22
ros__parameters:
33
takeoff_height: 5.0
44
high_takeoff_height: 5.0
5-
takeoff_landing_velocity: 0.3
5+
takeoff_velocity: 1.0
6+
landing_velocity: 0.3
67
takeoff_acceptance_distance: 0.3
78
takeoff_acceptance_time: 10.0
89
landing_stationary_distance: 0.02

robot/ros_ws/src/autonomy/3_local/b_planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_planner.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
class TakeoffLandingPlanner : public rclcpp::Node {
1717
private:
1818
// parameters
19-
float takeoff_height, high_takeoff_height, takeoff_landing_velocity;
19+
float takeoff_height, high_takeoff_height, takeoff_velocity, landing_velocity;
2020
float takeoff_acceptance_distance, takeoff_acceptance_time;
2121
float landing_stationary_distance, landing_acceptance_time;
2222
float landing_tracking_point_ahead_time;

robot/ros_ws/src/autonomy/3_local/b_planners/takeoff_landing_planner/src/takeoff_landing_planner.cpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,8 @@ TakeoffLandingPlanner::TakeoffLandingPlanner() : rclcpp::Node("takeoff_landing_p
44
// init parameters
55
takeoff_height = airstack::get_param(this, "takeoff_height", 0.5);
66
high_takeoff_height = airstack::get_param(this, "high_takeoff_height", 1.2);
7-
takeoff_landing_velocity = airstack::get_param(this, "takeoff_landing_velocity", 0.3);
7+
takeoff_velocity = airstack::get_param(this, "takeoff_velocity", 0.3);
8+
landing_velocity = airstack::get_param(this, "landing_velocity", 0.3);
89
takeoff_acceptance_distance = airstack::get_param(this, "takeoff_acceptance_distance", 0.1);
910
takeoff_acceptance_time = airstack::get_param(this, "takeoff_acceptance_time", 2.0);
1011
landing_stationary_distance = airstack::get_param(this, "landing_stationary_distance", 0.02);
@@ -65,13 +66,13 @@ TakeoffLandingPlanner::TakeoffLandingPlanner() : rclcpp::Node("takeoff_landing_p
6566
// track_mode_srv.request.mode = airstack_msgs::srv::TrajectoryMode::Request::TRACK;
6667
high_takeoff = false;
6768
takeoff_traj_gen =
68-
new TakeoffTrajectory(takeoff_height, takeoff_landing_velocity, takeoff_path_roll,
69+
new TakeoffTrajectory(takeoff_height, takeoff_velocity, takeoff_path_roll,
6970
takeoff_path_pitch, takeoff_path_relative_to_orientation);
7071
high_takeoff_traj_gen =
71-
new TakeoffTrajectory(high_takeoff_height, takeoff_landing_velocity, takeoff_path_roll,
72+
new TakeoffTrajectory(high_takeoff_height, takeoff_velocity, takeoff_path_roll,
7273
takeoff_path_pitch, takeoff_path_relative_to_orientation);
7374
// TODO: this landing point is hardcoded. it should be parameterized
74-
landing_traj_gen = new TakeoffTrajectory(-10000., takeoff_landing_velocity);
75+
landing_traj_gen = new TakeoffTrajectory(-10000., landing_velocity);
7576
current_command = airstack_msgs::srv::TakeoffLandingCommand::Request::NONE;
7677

7778
completion_percentage = 0.f;
@@ -192,10 +193,10 @@ void TakeoffLandingPlanner::timer_callback() {
192193
"TransformException in TakeoffMonitor landing tf lookup: " << ex.what());
193194
}
194195
bool tracking_point_check =
195-
(z_distance / takeoff_landing_velocity) > landing_tracking_point_ahead_time;
196+
(z_distance / landing_velocity) > landing_tracking_point_ahead_time;
196197
RCLCPP_INFO_STREAM(
197198
this->get_logger(),
198-
"landing: " << z_distance << " " << (z_distance / takeoff_landing_velocity) << " "
199+
"landing: " << z_distance << " " << (z_distance / landing_velocity) << " "
199200
<< landing_tracking_point_ahead_time << " " << tracking_point_check);
200201

201202
// ROS_INFO_STREAM("LANDING CHECK: " << time_diff << " " << time_check << " " <<

robot/ros_ws/src/robot_bringup/rviz/robot.rviz

Lines changed: 33 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -6,17 +6,13 @@ Panels:
66
Expanded:
77
- /Global Options1
88
- /TF1/Frames1
9-
- /Perception1
109
- /Sensors1
11-
- /Sensors1/Odometry1
10+
- /Perception1
1211
- /Local1
13-
- /Local1/DROAN1
14-
- /Local1/DROAN1/Trimmed Global Plan for DROAN1
1512
- /Local1/DROAN1/Trimmed Global Plan for DROAN1/Topic1
16-
- /Local1/Trajectory Controller1
1713
- /Global1
1814
Splitter Ratio: 0.590062141418457
19-
Tree Height: 701
15+
Tree Height: 570
2016
- Class: rviz_common/Selection
2117
Name: Selection
2218
- Class: rviz_common/Tool Properties
@@ -103,33 +99,32 @@ Visualization Manager:
10399
Show Axes: true
104100
Show Names: true
105101
Tree:
106-
map_FLU:
107-
base_link_ground_truth:
108-
base_link:
109-
base_link_frd:
110-
{}
111-
front_stereo:
112-
left_camera:
102+
world:
103+
map_FLU:
104+
base_link_ground_truth:
105+
base_link:
106+
base_link_frd:
113107
{}
114-
right_camera:
108+
front_stereo:
109+
left_camera:
110+
{}
111+
right_camera:
112+
{}
113+
ouster:
115114
{}
116-
ouster:
115+
map:
116+
base_link_stabilized:
117+
{}
118+
look_ahead_point:
119+
{}
120+
look_ahead_point_stabilized:
121+
{}
122+
map_ned:
123+
{}
124+
tracking_point:
125+
{}
126+
tracking_point_stabilized:
117127
{}
118-
map:
119-
base_link_stabilized:
120-
{}
121-
look_ahead_point:
122-
{}
123-
look_ahead_point_stabilized:
124-
{}
125-
map_ned:
126-
{}
127-
tracking_point:
128-
{}
129-
tracking_point_stabilized:
130-
{}
131-
world:
132-
{}
133128
Update Interval: 0
134129
Value: true
135130
- Class: rviz_common/Group
@@ -509,7 +504,7 @@ Visualization Manager:
509504
Views:
510505
Current:
511506
Class: rviz_default_plugins/Orbit
512-
Distance: 11.010651588439941
507+
Distance: 14.042609214782715
513508
Enable Stereo Rendering:
514509
Stereo Eye Separation: 0.05999999865889549
515510
Stereo Focal Distance: 1
@@ -524,10 +519,10 @@ Visualization Manager:
524519
Invert Z Axis: false
525520
Name: Current View
526521
Near Clip Distance: 0.009999999776482582
527-
Pitch: 0.365399032831192
522+
Pitch: 0.5953989028930664
528523
Target Frame: base_link
529524
Value: Orbit (rviz)
530-
Yaw: 1.8053982257843018
525+
Yaw: 1.1703985929489136
531526
Saved: ~
532527
Window Geometry:
533528
Displays:
@@ -536,10 +531,10 @@ Window Geometry:
536531
collapsed: false
537532
Front Left RGB:
538533
collapsed: false
539-
Height: 1022
534+
Height: 1140
540535
Hide Left Dock: false
541536
Hide Right Dock: false
542-
QMainWindow State: 000000ff00000000fd0000000400000000000001e500000334fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000334000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000002eb000000c9000000000000000000000001000001f600000334fc0200000007fb00000016004c006500660074002000430061006d006500720061010000003b000001880000000000000000fb00000014004c006500660074002000440065007000740068010000003b0000016a0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001c00460072006f006e00740020004c0065006600740020005200470042010000003b000001610000002800fffffffb0000002000460072006f006e00740020004c00650066007400200044006500700074006801000001a2000001cd0000002800fffffffb0000000a00560069006500770073000000025900000114000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074a0000006efc0100000002fb0000000800540069006d006501000000000000074a0000025300fffffffb0000000800540069006d00650100000000000004500000000000000000000003630000033400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
537+
QMainWindow State: 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
543538
Selection:
544539
collapsed: false
545540
Time:
@@ -550,6 +545,6 @@ Window Geometry:
550545
collapsed: false
551546
Visual Odometry Features:
552547
collapsed: false
553-
Width: 2490
554-
X: 1990
555-
Y: 27
548+
Width: 2190
549+
X: 245
550+
Y: 72

0 commit comments

Comments
 (0)