Skip to content

Commit 6d8a739

Browse files
committed
Fix bug in the example calling wrong goto command in each section
1 parent 937f44d commit 6d8a739

File tree

2 files changed

+5
-5
lines changed

2 files changed

+5
-5
lines changed

docs/examples/guided-set-speed-yaw-demo.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -158,7 +158,7 @@ The functions for controlling vehicle movement are:
158158
* :ref:`goto_position_target_global_int() <example_guided_mode_goto_position_target_global_int>` is a position controller that uses the `SET_POSITION_TARGET_GLOBAL_INT <https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_GLOBAL_INT>`_ command.
159159
* :ref:`goto_position_target_local_ned() <example_guided_mode_goto_position_target_local_ned>` is a position controller that uses `SET_POSITION_TARGET_LOCAL_NED <https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_LOCAL_NED>`_ command (taking values in NED frame, relative to the home position). This is used to fly a square path. The script is put to sleep for a certain time in order to allow the vehicle to reach the specified position.
160160
* :ref:`send_ned_velocity() <guided_mode_copter_velocity_control>` is a velocity controller. It uses `SET_POSITION_TARGET_LOCAL_NED <https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_LOCAL_NED>`_ to fly a square path using velocity vectors to define the speed in each direction.
161-
* :ref:`send_global_velocity() <example_guided_mode_send_global_velocity>` is a velocity controller. It uses `SET_POSITION_TARGET_GLOBAL_INT <https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_GLOBAL_INT>`_ to fly a diamond-shaped path. The behaviour is essentially the same as for ``send_ned_velocity()``.
161+
* :ref:`send_global_velocity() <example_guided_mode_send_global_velocity>` is a velocity controller. It uses `SET_POSITION_TARGET_GLOBAL_INT <https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_GLOBAL_INT>`_ to fly a diamond-shaped path. The behaviour is essentially the same as for ``send_ned_velocity()`` because the velocity components in both commands are in the NED frame.
162162
* :ref:`goto <example_guided_mode_goto_convenience>` is a convenience function for specifying a target location in metres from the current location and reporting the result.
163163

164164

examples/guided_set_speed_yaw/guided_set_speed_yaw.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -430,7 +430,7 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z):
430430
goto(0, 100)
431431

432432
print("Position North -80 West 50")
433-
goto(-80, -50, goto_position_target_global_int)
433+
goto(-80, -50)
434434

435435

436436

@@ -452,15 +452,15 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z):
452452

453453
print("Set speed to 5m/s.")
454454
set_speed(5)
455-
goto(-100, -130)
455+
goto(-100, -130, goto_position_target_global_int)
456456

457457
print("Set speed to 15m/s (max).")
458458
set_speed(15)
459459
print("Position South 0 East 200")
460-
goto(0, 260)
460+
goto(0, 260, goto_position_target_global_int)
461461

462462
print("Set speed to 10m/s (max).")
463-
set_speed(10)
463+
set_speed(10, goto_position_target_global_int)
464464

465465
print("Position North 100 West 130")
466466
goto(100, -130, goto_position_target_global_int)

0 commit comments

Comments
 (0)