MAVSDK-Python
MAVSDK-Python copied to clipboard
Can't change takeoff altitude using set_takeoff_altitude()
Hey guys, I tried to change the altitude in takeoff_and_land.py through the following code but ran into an error. Looks like a bug. Would be grateful for insights and help on this!
#!/usr/bin/env python3
import asyncio
import time
from mavsdk import start_mavlink
from mavsdk import connect as mavsdk_connect
start_mavlink()
drone = mavsdk_connect(host="127.0.0.1")
async def run():
print("Waiting for drone...")
async for state in drone.core.connection_state():
if state.is_connected:
print(f"Drone discovered with UUID: {state.uuid}")
break
print("-- Arming")
await drone.action.arm()
print("-- Taking off")
await drone.action.set_takeoff_altitude(100)
print (await drone.action.get_takeoff_altitude())
await drone.action.takeoff()
await asyncio.sleep(30)
print("-- Landing")
await drone.action.land()
loop = asyncio.get_event_loop()
loop.run_until_complete(run())
Terminal output:
python3 takeoff_and_land.py
Waiting for drone...
Drone discovered with UUID: 5283920058631409231
-- Arming
-- Taking off
Traceback (most recent call last):
File "takeoff_and_land.py", line 36, in <module>
loop.run_until_complete(run())
File "/usr/lib/python3.6/asyncio/base_events.py", line 484, in run_until_complete
return future.result()
File "takeoff_and_land.py", line 25, in run
await drone.action.set_takeoff_altitude(100)
File "/usr/local/lib/python3.6/dist-packages/mavsdk/plugins/action.py", line 331, in set_takeoff_altitude
raise ActionError(result, "set_takeoff_altitude()", altitude)
mavsdk.plugins.action.ActionError: UNKNOWN: ''; origin: set_takeoff_altitude(); params: (100,)
Sorry for the delay @aydal, I've been a bit overwhelmed.
I'm thinking that you may actually contribute to that issue, as now you are familiar with gRPC from the PositionNED
PR :-).
If you look at SetTakeoffAltitude
:
grpc::Status SetTakeoffAltitude(
grpc::ServerContext* /* context */,
const rpc::action::SetTakeoffAltitudeRequest* request,
rpc::action::SetTakeoffAltitudeResponse* /* response */) override
{
if (request != nullptr) {
const auto requested_altitude = request->altitude();
_action.set_takeoff_altitude(requested_altitude);
}
return grpc::Status::OK;
}
You can see that response
is ignored. Which is wrong: we need to respond with an ActionResult
, as defined by the proto file.
SetMaximumSpeed
, in the same file, does it the right way:
grpc::Status SetMaximumSpeed(
grpc::ServerContext* /* context */,
const rpc::action::SetMaximumSpeedRequest* request,
rpc::action::SetMaximumSpeedResponse* response) override
{
if (request != nullptr) {
const auto requested_speed = request->speed();
mavsdk::Action::Result action_result = _action.set_max_speed(requested_speed);
if (response != nullptr) {
auto* rpc_action_result = new rpc::action::ActionResult();
rpc_action_result->set_result(
static_cast<rpc::action::ActionResult::Result>(action_result));
rpc_action_result->set_result_str(mavsdk::Action::result_str(action_result));
response->set_allocated_action_result(rpc_action_result);
}
}
return grpc::Status::OK;
}
i.e. SetMaximumSpeed
does put the ActionResult
into the response
.
Would you mind fixing SetTakeoffAltitude
such that it behaves correctly? That would be awesome :sunglasses:.
Hello Jonas, Apologies for the late reply. Have built and checked the changes. Changes visible on PR
Which PR?
@aydal: Any news on that? I remember you worked on that but I lost track eventually :confused:.
I had the same issues but I used some other work around by setting the takeoff height parameter, MIS_TAKEOFF_ALT
await drone.param.set_float_param("MIS_TAKEOFF_ALT", 20.0)
20.0 metres was the height in my case. That should suffice for now.
That works, of course, but the fix suggested above would be cleaner. It should not be difficult to fix, and I believe @aydal had it but just did not open a PR with it :confused:.
Alright then, let me give it a shot.
@vizzbee: sure, it would be awesome!
I don't remember that PR or why it did not get merged. The easiest would probably be to open a PR specific to that bugfix, so that it is easier to merge it. If you do it along with a new feature, it will take more time to get merged :slightly_smiling_face:.
Hi, has the bug been resolved? I tried to modify the takeoff altitude on takeoff example file and still get an error.
@siddux let me check. I see the last status here: https://github.com/mavlink/MAVSDK/pull/958
I have updated the pull request. I hope that we can merge it soon now.
The PR has been merged, this should be fixed in the next release.
This issue is marked as closed, but it seems to still be an issue. I ran similar code as shown above, calling the set_takeoff_altitude() command as follows:
await drone.action.set_takeoff_altitude(5.0)
The code throws and invalid parameter exception but still sets the altitude value. I can confirm this by calling the get method and verify that it was in fact changed. I am running version 0.12.0 of mavsdk on a raspberry pi.
I am running version 0.12.0 of mavsdk on a raspberry pi.
@cryptik Can you try the latest version 1.4.0?
Sorry... I gave you the version I am running on locally on MacOS. I deploy remotely to RPi.. will check the version when I am back at the drone. Another question... for the Mac, it appears the latest version is 0.12.0? I have an M1... is that the latest version?
M1 is tricky as we don't have mavsdk_server
built in CI for it yet. See https://github.com/mavlink/MAVSDK-Python/issues/319.
You can get try to get the latest with python -m pip --upgrade install mavsdk
Thanks, but worries.. there are other issues I have with the M1 and related libraries... so the remote build on RPi works fine. Will check the version and report back.
When I do the upgrade on the M1, it tells me the requirement is already met... for version 0.12.0. Seems consistent with what is discussed in #319.
Ok, I checked... on the RPi, I am using mavsdk 1.4.0 which I assumed had this problem corrected... but maybe not for the Pi. I currently catch the exception and then call the get function to confirm that it was actually changed.
That's odd. It definitely should have been fixed in 1.4.0. I will try to reproduce this.