Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move calibration from commander to event framework #8706

Closed
wants to merge 8 commits into from

Conversation

sugnanprabhu
Copy link
Contributor

@sugnanprabhu sugnanprabhu commented Jan 16, 2018

This patch moves all calibration routines out of commander to events framework and removes commander_low_prio_loop.

Includes following set of changes.

On receiving calibration request
i. commander does some minimal handling and move the arming state to ARMING_STATE_INIT.
ii. event framework waits until the arming state is moved to ARMING_STATE_INIT before timeout of 2secs.
event framework spawns a px4 task to handle the calibration and make sure only one calibration is active.
event framework sends a calibration_status orb message after the completion of the calibration.
Commander will move the arming state back to ARMING_STATE_STANDBY once it receives calibration_status.
This is one of the part of t

Rebase of #8200 #8630

@@ -59,7 +59,7 @@

#include "calibration_routines.h"
#include "calibration_messages.h"
#include "commander_helper.h"
#include <commander/commander_helper.h>
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@dagar
airspeed_calibration.cpp and calibration_routines.cpp are using following routines
tune_neutral,
tune_negetive,
tune_positve,
set_tune,
rgbled_set_color_and_mode

As the routines are used by commander as well, we have three options.

  1. Have same routines in calibration, which will lead to duplication of code (This might need some testing of all the cases).
  2. include "commander/commander_helper.h" in airspeed_calibration.cpp and calibration_routines.cpp for now.
  3. commander_helper.cpp mainly has led and tune related code, move this code to someother location and use it in both module (commander and callibration).

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  1. expose tunes via uORB - Tunes library #8679

@r0gelion
Copy link
Contributor

This PR is the continuation of the PR #8630 which is closed and had @px4/testflights as a reviewer. Please add this reviewer when the PR is ready for flight testing.

@sugnanprabhu sugnanprabhu force-pushed the mv_calibration branch 2 times, most recently from 433cc5c to 62145a4 Compare January 18, 2018 09:45
@sugnanprabhu
Copy link
Contributor Author

sugnanprabhu commented Jan 18, 2018

Changes made depends on #8679, build is expected to fail.
But tested the changes applying the patches on top #8679

@dagar
Copy link
Member

dagar commented Jan 29, 2018

@sugnanprabhu the tunes library is finally in! If you have time this week let's sync up and work on finally getting this merged.

@dagar dagar self-assigned this Jan 29, 2018
@dagar dagar added this to the Release v1.8.0 milestone Jan 29, 2018
@sugnanprabhu
Copy link
Contributor Author

sure @dagar I will rebase the changes and run some basic tests.

@dagar
Copy link
Member

dagar commented Jan 29, 2018

Great! I'll test and review on my end as soon as this PR is updated.

@sugnanprabhu
Copy link
Contributor Author

@dagar
I have rebased the changes. but I'm observing one issue related to led which I'm debugging.
Earlier if one of the sensor is not calibrated, the led used to blink red and fast but now it is blinking normal blue.

@sugnanprabhu
Copy link
Contributor Author

@dagar

Found a bug in state_machine_helper.cpp, please correct me if this was intentional.

arming_state_transition is setting condition_system_sensors_initialized to 1 even if the preflight check fails,
status_flags->condition_system_sensors_initialized = (prearm_ret == OK);
https://github.com/PX4/Firmware/blob/master/src/modules/commander/state_machine_helper.cpp#L191

The reason why this bug goes hidden is that, condition_system_sensors_initialized is set to 0 in commander_low_prio_thread just before calling arming_state_transition
https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L4266

arming_state_transition is also called from commander main thread, which is is running on higer priority, so even before the arming_state_transition is called in the commander_low_prio_thread, it is called in the following.
so condition_system_sensors_initialized is still 1 and the buggy code never executes as the second call to arming_state_transition sees that the state is already changed to ARMING_STATE_STANDBY.

https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L2316

@@ -330,7 +330,7 @@ transition_result_t arming_state_transition(vehicle_status_s *status,
}

feedback_provided = true;
valid_transition = false;
valid_transition = true;
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Preflight check during transition to ARMING_STATE_STANDBY shouldn't cause the state transition to fail.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why not, isn't that its purpose?

ARMING_STATE_STANDBY = preflight checks passed?

Copy link
Contributor Author

@sugnanprabhu sugnanprabhu Apr 19, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @dagar, @mhkabir
Sorry for the late reply, I'm out of country and do not have access to mail.

When I added this change I was facing some timing issue related to arming_state_transition.
The timing issue stayed hidden when the arming_state_transition is called from the low_prio_thread. As the calibration was moved to the the main thread, it was retuning TRANSITION_DENIED for the following.
https://github.com/PX4/Firmware/pull/8706/files#diff-1d51a813dcb26f46616f71f28aacc70dR1079

I already explained about the timing issue that was observed earlier in the following comment, when I made this change. Please note that the line numbers are changed in the mainline code and the line numbers mentioned in the comment do not match any more.
#8706 (comment)

I see recently there has been many fixes in state_machine_helper.cpp, I think removing this condition might work now. I can check on the actual hardware only after I return in few days.

@sugnanprabhu
Copy link
Contributor Author

@dagar did you get a chance to try the changes, can this changes be tested by the testflight team?

@dagar
Copy link
Member

dagar commented Feb 8, 2018

Overall it's very close to mergeable, but I need to sit down and go through the intended LED and buzzer behaviour.

@LorenzMeier
Copy link
Member

@PX4/testflights Could you please test a fresh vehicle setup and flight and see if it checks out?

@LorenzMeier LorenzMeier requested a review from a team February 9, 2018 21:42
@Avysuarez
Copy link

flight with pixhawk Pro (V4pro) Good flight, no issues.
https://review.px4.io/plot_app?log=d498f55e-3312-418d-a4bc-c21a7f479ab9

flight with pixhawk1 (V2) Good flight, no issues
https://review.px4.io/plot_app?log=e71d8198-7e5b-4817-b9e3-e09c44e20512

@dannyfpv
Copy link

dannyfpv commented Feb 9, 2018

test fligth pix mini (v3) flight better
https://logs.px4.io/plot_app?log=690932bb-93af-4f14-a5f7-decd7dbb3d60

@dagar
Copy link
Member

dagar commented Mar 7, 2018

I rebased and made one small change. The main thing we need to do here is go through all the intended buzzer and led usage and ensure it's actually working correctly.

This patch moves all the calibration routines out of commander to
events framework. Also removes low prio thread from commander.

Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
sugnanprabhu and others added 5 commits March 29, 2018 12:17
Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
arming_state_transition function in state_machine is setting
condition_system_sensors_initialized to wrong value
if condition_system_sensors_initialized is set to 0 before
calling it.

Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
@dagar
Copy link
Member

dagar commented Mar 29, 2018

I'm not quite sure about the vehicle_command interaction here. Both commander and events seem to be responding to the same command in some situations.

I think events need to completely own the calibration commands, and use some other mechanism to ask commander to enter ARMING_STATE_INIT, wait for verification, run calibration, then end. During calibration events should periodically tell commander what's happening to prevent it from running preflight checks again and trying to transition to ARMING_STATE_STANDBY.

@mhkabir
Copy link
Member

mhkabir commented Apr 16, 2018

@sugnanprabhu Any updates here based on @dagar's comments?

@dagar dagar removed this from the Release v1.8.0 milestone May 4, 2018
@Tony3dr
Copy link

Tony3dr commented Jul 4, 2018

@dagar do you need @PX4/testflights to test this pull request again?

@dagar dagar removed the request for review from a team September 19, 2018 23:00
@stale
Copy link

stale bot commented Jan 20, 2019

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

@stale
Copy link

stale bot commented Feb 4, 2019

Closing as stale.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

8 participants