Closed LorenzMeier closed 9 years ago
Also needed: send a MAV_CMD_NAV_GUIDED_ENABLE message to switch to offboard
Hi, I've been trying to adapt the above example to set the mode to offboard and set the position setpoint to some value.
My first issue is that it doesn't seem that the MAV_CMD_NAV_GUIDED_ENABLE is being received properly (QGC doesn't even display the 'rejected' message). My setup and procedure are as follows:
Is this approximately what is required to set it to offboard mode? I get the same response regardless of which I mode the pixhawk is in prior to launching the script.
The MAVlink app is not running by default on the USB console. USB is not a safe in-flight link, so you will want to wire up telem 2 with a FTDI cable anyway as first step.
Fair point, but shouldn't the controller receive the command regardless? I'm sending the command via MavLink over an FTDI radio on telem1 and using the USB connection to basically monitor the pixhawk's response in QGC.
Hoi zaeme!
My name is Trent, I study aircraft design and build UAV's for fun. A couple buddies and I help run a UAV club, can check it out here -- uav.stanford.edu. Quite a few people are playing with Pixhawks there, and there's a growing interest in running missions via companion computers.
I've been massaging the c_uart example here -- https://github.com/aerialhedgehog/c_uart_interface_example
Apologies in advance, this is not in PX4 style yet (I spend most of my time with that snakey scripting language ;). Will be happy to bring this into style if you think it's moving in the right direction.
Right now I'm still trying to make sure data is receiving and sending properly from the off-board computer. Messages are receiving just fine. However at the moment, messages aren't being processed by Pixhawk.
Here's the test I'm running on Pixhawk at the moment, would be nice to get another set of eyes on this because I've hit a roadblock ---
Added print statements in MavlinkReceiver::receive_thread()
within the file mavlink_receiver.cpp
.
[line 1343]
while (!_mavlink->_task_should_exit) {
if (poll(fds, 1, timeout) > 0) {
/* non-blocking read. read may return negative values */
if ((nread = read(uart_fd, buf, sizeof(buf))) < (ssize_t)sizeof(buf)) {
/* to avoid reading very small chunks wait for data before reading */
usleep(1000);
}
printf("\n");
printf("received\n");
/* if read failed, this loop won't execute */
for (ssize_t i = 0; i < nread; i++) {
printf("%i ",buf[i]);
if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &status)) {
/* handle generic messages and commands */
printf("handle\n");
handle_message(&msg);
/* handle packet with parent object */
_mavlink->handle_message(&msg);
}
}
/* count received bytes */
_mavlink->count_rxbytes(nread);
}
}
When I send the message from c_uart_interface_example, this is what is printed on the PIxhawk's Nuttix shell --
received
53 0 1 50
received
0 0 0 0 0 0 0 0 0 0 0 0 160 12 70 0 0 0 0 0 0 0 0 0 0 0 0 0
received
So the parsing state is getting stuck in MAVLINK_PARSE_STATE_IDLE.
If you have a quick minute, would you mind taking a look at my c_uart_interface_example, to maybe check for a silly mistake on the writing side? I'd be super grateful.
This is where the message is built -- https://github.com/aerialhedgehog/c_uart_interface_example/blob/master/mavlink_serial.cpp#L89
This is where the write to port happens -- https://github.com/aerialhedgehog/c_uart_interface_example/blob/master/serial_port.cpp#L78
Also will be happy to pull-request this back if it seems useful for others.
Many thanks,
Hardware strikes again.. Turns out my board's Serial 5 RX is not working. Switched over to Serial 4 and saw the messages being handled properly.
I can start cleaning my code up in the next day. If anyone else is working on the c_uart_interface_example, let me know, I don't want to step on your toes!
This example is closely related to what I'm trying to achieve with my project, so I've also been working on this example. So far, I've managed to do the following:
The mode setting and setpoints were confirmed with QGC.
The code can be seen here https://github.com/jayceelock/c_uart_interface_example. I'm still playing around with the code, and there are still some things I want to implement/change/investigate, like automate the whole flight process from take-off to offboard control and finally to landing. If anyone would find the code helpful, just let me know and I'd be happy to clean it up and write a proper README and maybe pull-request this back to the project repo.
Hey Jaycee! Glad to see someone else wants to work on this too! What do you think about collaborating? I've been able to tidy up most of the send receive parts and write the readme tutorial that goes with it. Would you mind taking a look at it? Looks like you have been able to make the second part work, which is getting the quad to respond to the command by being in the right mode. We should find a way to merge these. https://github.com/aerialhedgehog/c_uart_interface_example
Lorenz, referencing your post on the forum, this code is public domain at the moment, maybe we should move it over to BSD? In which case where should the copyright go - mavlink? px4?
BSD + MAVLink makes probably most sense, as its part of the MAVLink organization.
got it, sounds great, thanks!
On Tue, Nov 25, 2014 at 12:06 AM, Lorenz Meier notifications@github.com wrote:
BSD + MAVLink makes probably most sense, as its part of the MAVLink organization.
— Reply to this email directly or view it on GitHub https://github.com/mavlink/c_uart_interface_example/issues/6#issuecomment-64322997 .
Hi, I am new in using Mavlink messages and I like to follow your experiences in sending High-level control commands to the low-level control system. I want to start using c_uart_interface_example and I would like to know which types of Firmware is needed on the pixhawk?
Particularly, I've used the APM firmware which for pixhawk runs on top of the PX4. In this case, does the APM firmware can successfully receive and forward the Mavlink message to the PX4 firmware or it is not possible to use the APM firmware on pixhawk for sending off-board command?
I would be grateful if you may help me.
hey there! great question, i think it might be best answered on the px4users forum so more people can benefit from it, find my answer here -- https://groups.google.com/forum/#!topic/px4users/IC1iz_TsL_Y
Hi Everyone,
Unfortunately have been banging my head against walls for the past two days with this example.
When sending x-y-z position commands, the autopilot works its way into a state that sets throttle to zero. I've seen this by watching logs and by watching my hex fall out of the sky (was keeping it low to the ground tho so it's fine).
When sending velocity vx-vy-vz commands this failure mode doesn't appear. I've poked around with print statements for a few hours but came up dry. All I could see is that it detects landing because of the throttle cut almost as soon as offboard control starts.
I was wondering if anyone with more knowledge of the mc controller or commander had any ideas how this would happen?
Thanks!
PS Many thanks to Jaycee for bringing the code this far!
Hi,
I ran more flight tests today, varying commands with different bitmasks. This what I observed:
Constant for all tests
Dear Trent,
I forked your repo and did some tests for the past few days. I was able to send position set points and have the UAV perform a square flight. I was only setting the bits for position, velocity and yaw. The performance was quite good for a first trial, mind you I was using indoor localization system and performing the transformation and sending it via mavros using the visionestimation plugin. I used both, a radio link to send the position setpoint, and a mavros link to send the local position updates. I will post a video and the log shorty.
I have a nice setup for testing now, so if you want we can collaborate on doing some more tests. Saturday I will be back in the lab, and I am planning to do some more tests and see if I can do some figure8 or circle. If you have any test scenarios you would like me to assist you with then I would be glad to do it.
Cheers
here is the video link: http://www.youtube.com/watch?v=Tve1ADZqgOM
awesome tarek! glad to hear this is working indoor. it would be great to have another collaborator with jaycee and i. i see you're using the object branch, great this is more reusability oriented, the master is more instructive. i just pushed a bunch of changes to the object branch, to implement an autopilot interface object. give this a look, and when you get a chance can you merge it to your fork? i'll sketch a test plan for us by tomorrow. the biggest thing i'd like to understand and de-risk at the moment is the motor-cut behavior i described in a post above. many thanks!
Hi Tarek and Trent,
It would be great to get your changes back into mainline of the Firmware and interface repos. And it would be really cool if you would be willing to write a tutorial in the wiki. Given the state you have there should not be much missing, and I'd be happy to invest some time helping with the integration.
Cheers, Lorenz
Thanks Lorenz! Not sure I'd feel comfortable merging upstream while the motors are cutting out on me. Do you have any idea for what could be causing a throttle cut when not sending velocity setpoints?
Hi Tarek and Trent,
It would be great to get your changes back into mainline of the Firmware and interface repos. And it would be really cool if you would be willing to write a tutorial in the wiki. Given the state you have there should not be much missing, and I'd be happy to invest some time helping with the integration.
Cheers, Lorenz
— Reply to this email directly or view it on GitHub https://github.com/mavlink/c_uart_interface_example/issues/6#issuecomment-65676861 .
Could you go a bit more into detail? They cut power if you stop sending set points? That would be the intended behaviour, as the whole control system is designed to time out - imagine a quad taking off in the lab because you accidentally cut power to the control computer!
I'm open to fallback to onboard control, but that's not easy to get right - so when you can pick between power cut and a system completely out of control spinning blades, it becomes clear that the throttle cut is the better option.
Trent, Lorenz is correct, what we noticed was that once you stop sending the setpoints the system goes into manual mode and you have to take over the control immediately or the UAV will immediately go down. I think the code should be modified so that it switches to POSCRL mode once you stop sending setpoints, this way it will stay were it is (if that's the intended behaviour in the use case scenario).
I will merge your latest changes into the object branch of my fork and give it a go on Saturday.
Lorenz, I will document in details the procedures in the pixhawk wiki (I think I already have an account there), any particular link you want that tutorial under ?
Trent, think about few tests that we can perform (additional to the ones that I will be performing), I will do these tests on Saturday and post my results.
We are finally getting somewhere, hopefully we can organise our efforts and get the offboard control working nicely.
Cheers, Tarek
On Thu, Dec 4, 2014 at 10:54 PM, Lorenz Meier notifications@github.com wrote:
Could you go a bit more into detail? They cut power if you stop sending set points? That would be the intended behaviour, as the whole control system is designed to time out - imagine a quad taking off in the lab because you accidentally cut power to the control computer!
I'm open to fallback to onboard control, but that's not easy to get right
- so when you can pick between power cut and a system completely out of control spinning blades, it becomes clear that the throttle cut is the better option.
— Reply to this email directly or view it on GitHub https://github.com/mavlink/c_uart_interface_example/issues/6#issuecomment-65682491 .
Happy to go into more detail. This is one of the sanity checks that would be nice to have from another perspective to see if I'm just being silly somewhere.
The throttle cut I've observed happens while I'm in the middle of streaming a properly bookended position control command.
In detail, the order of events from the perspective of the companion computer side are --
I've tested the case when streaming stops before ending offboard control. The quad goes into failsafe, and for me goes back into position control mode, but beeps the failsafe warning. I can land it manually then. I havn't set return to launch failsafe, which is maybe why i can do this.
Some Tests. Feel free to make changes, these are just sketches and suggested. I am very curious though what happens if you do the first test, so hit this one at least if you can.
This is with the object branch of aerialhedgehog/c_uart_interface_example
The following tests exercise the different setpoint commands. If you have time to do one, do the first one.
Further Exploration - Try the yaw setpoints commands set_yaw(yaw,&sp) set_yawrate(yaw,&sp) Add more fun logic to the command() function
One related issue we found was the mavlink_command_long_t message has an arm/disarm command embedded in param 1 for mode switch. This was causing it to disarm immediately upon entering offboard mode. If your code is sending the offboard command about 2 seconds after step 3 as you indicate, this might be the issue.
The exact parameters we are sending for offboard in the mavlink_command_long_t message are param1 = 209 and param2= 6. See also MAV_CMD_DO_SET_MODE and MAV_MODE_FLAG.
Another debugging tip - take the props off and run your test on a bench while arming/disarming it and switching modes. You can see the local_position_setpoint messages you are sending in qground, and you will save your quad from a few hard landings :)
This might be an intricacy of our test set up, but the fail safe behavior we've observed is when we stop sending setpoints the alarm goes off, the system goes into auto-land, and stays armed. This seems preferable to cutting throttle in outdoor environments.
Trent,
Just a quick update, we did some tests today including your fist 2 tests. I could not replicate your behavior, I never had any throttle cut-off. What I noticed was the following:
The only different thing I did from your test procedures was going from manual->offboard directly, I didn't switch to POSCRL before going to offboard, so I am not sure if this causes the cut-off.
I didn't manage to do all the tests I wanted because I was having issues with my tracker, and I didn't have enough batter charged, so I will do more tests this week.
Cheers, Tarek
Hi all,
Could we maybe get the current WIP state you have for all changes that you might have applied into a pull request to ease the review? So one pull request for PX4/Firmware and one pull request for the c_uart example repo.
The speed handling you are looking for is somewhere here, and inserting the velocity constraint there should do the trick: https://github.com/PX4/Firmware/blob/master/src/modules/mc_pos_control/mc_pos_control_main.cpp#L837
Let me know if I can assist further.
@thomasgubler let us know if you have further comments.
pull request submitted. https://github.com/mavlink/c_uart_interface_example/pull/9
i haven't made any changes to px4/firmware
@stebl thanks for the info. i tried your param setup but it didn't help. i'm only sending the offboard command once at start and once at end. just to confirm, could you post the code for your mode command?
@blackcoder ok good to know, maybe running indoor localization is an important difference. i'm running outdoors.
i ran the example again today, the throttle still cuts when i send position commands only.
attaching a plot of the servo commands logged on board, annotated with the mavlink messages corresponding to the major events.
@LorenzMeier @thomasgubler i think it might be useful to be able to pull the mode out of off-board control via a mode switch. I see that there was a discussion regarding modeswitching from rc here. However, if mavlink was used to start offboard mode, i would think we should still be able to switch back to manual mode in an emergency. this doesn't seem possible at the moment, was it intended?
let me know if we should move this to a separate issue/topic.
many thanks for the advice and support!
@aerialhedgehog your cut-off is puzzling, maybe the vision circuit breaker (needed to use vision position) introduces different behaviour.
Regarding the offboard RC control, I am already doing it, I've mapped one of my RC channels above a certain threshold to enable/disable the offboard control and it's quite handy when there is an emergency.
Cheers, Tarek
Oh cool! This is even with signaling the start of offboard mode via mavlink?
@aerialhedgehog https://github.com/aerialhedgehog your cut-off is puzzling, maybe the vision circuit breaker (needed to use vision position) introduces different behaviour.
Regarding the offboard RC control, I am already doing it, I've mapped one of my RC channels above a certain threshold to enable/disable the offboard control and it's quite handy when there is an emergency.
Cheers, Tarek
— Reply to this email directly or view it on GitHub https://github.com/mavlink/c_uart_interface_example/issues/6#issuecomment-65928503 .
@aerialhedgehog Yes it does.
@LorenzMeier regarding the speed, so basically you need to read the velocity setpoint and scale the speed vector to the setpoint instead of the maximum speed when performing position control ? Is it hard to do ?
@LorenzMeier @thomasgubler i think it might be useful to be able to pull the mode out of off-board control via a mode switch. I see that there was a discussion regarding modeswitching from rc here. However, if mavlink was used to start offboard mode, i would think we should still be able to switch back to manual mode in an emergency. this doesn't seem possible at the moment, was it intended?
Yes that was intended. This was to prevent the system switching back out of offboard when you switch to offboard via mavlink but have the RC switch still on onboard. We could change the functionality of the RC switch. Instead of the offboard yes/no functionality we could call it 'RC override'. Which means: switch deactivated: system can go to offboard and stays in offboard if asked to so via mavlink switch activated: RC has priority regardless of what mavlink asks
The speed handling you are looking for is somewhere here, and inserting the velocity constraint there should do the trick: https://github.com/PX4/Firmware/blob/master/src/modules/mc_pos_control/mc_pos_control_main.cpp#L837 Let me know if I can assist further. @thomasgubler let us know if you have further comment
For offboard the read in is here. https://github.com/PX4/Firmware/blob/master/src/modules/mc_pos_control/mc_pos_control_main.cpp#L651 This is implemented exactly how you describe it. If you send both (pos sp and vel sp) only the pos sp is used. This is a bit tricky and application dependent. E.g.: What should the system do when it is very close to the position setpoint but you ask for a (high) velocity not directed towards the setpoint?
@thomasgubler you are right, it is a bit tricky, but having this functionality is essential for certain applications. My main target is indoor environments, so moving slowly indoor is crucial, I am currently considering the following options:
Any comments on these three options?
Has anyone here any issue with replacing the mavlink files in the repo with a submodule? Reviewing PRs which contain MAVLink updates are impossible to review due to the file changes.
ah i can start a submodule, one minute
What should the system do when it is very close to the position setpoint but you ask for a (high) velocity not directed towards the setpoint?
Yeah very true, maybe it should be organized this way -- position triplet, velocity magnitude, acceleration magnitude where velocity and acceleration setpoints are optional. maybe the magnitudes are inferred as the magnitude of the velocity and acceleration triplet.
@aerialhedgehog I've uploaded the code snippet we are testing with. It's very messy and has some of our application libraries in it (LCM and Poco). See https://github.com/stebl/local_pos_setpoint/blob/master/local_pos_setpoint.cpp#121 and it's called here before the main loop https://github.com/stebl/local_pos_setpoint/blob/master/local_pos_setpoint.cpp#271.
We also have the RC switch mapped to offboard. With a 3-way toggle it is mapped to manual, position control, then offboard. This allows us to switch back to manual in case of an emergency. Another thing to note is this works when setting modes through the mode switch command, but mav_cmd_nav_guided_enabled will override the RC.
thanks @stebl! your code looks great. i can see how you setup the command. there are a few differences i noticed between what you're doing and what i'm doing --
will try a few of these things out later today
update, re previous post
Hi It would be nice if you cold consolidate your improvements into a PR for the PX4 repo as well.
I think we can close this issue
@julianoes @thomasgubler Issue to track the relevant discussion here: https://groups.google.com/forum/#!topic/px4users/IC1iz_TsL_Y
For all people interested to send high-rate set points offboard: What needs to be done is:
Having an example ready that works out of the box would be a huge step forward.