jtanx / picopterx

FYP 2015 Hexacopter project 🚁🚁🚁🚁
2 stars 1 forks source link

ArduPilot yaw control #65

Open jtanx opened 9 years ago

jtanx commented 9 years ago

See commit message for f61e6ef3aa4a64792815b42a81fcf06911c68dbe.

Another option may be to override the RC channel, but looking at it, this sounds slightly dangerous. I'm also not convinced that it will only accept these RC override commands in guided mode only.

jtanx commented 9 years ago

It's how mavproxy controls rc channels...

RC_CHANNELS_OVERRIDE ( #70 ) _The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

jtanx commented 9 years ago

RC channel map:

  1. Roll
  2. Pitch
  3. Throttle
  4. Yaw
jtanx commented 9 years ago

Meh, I was able to do the NED->body conversion by knowing the current yaw of the copter and performing a translation. Seems to work in the simulator, but I don't know how well it will work in the real world.

BrettRD commented 9 years ago

SetYaw needs its input sanitised. It accepts 0-360, and endlessly flips from due east to due west and back if you feed it -90. Workaround:

    if(phi<0) phi +=360;
    fc->fb->SetYaw(phi, false);
jtanx commented 9 years ago

Blegh had to resolve an unrelated issue before I could test this (750d6b1b4070a409603e9adc0c9c50577a1414fd).

I cannot reproduce the issue. If I feed a negative angle (is_relative=false), then it just goes to the positive of that angle, e.g. 90 degrees/West. I am currently on the AC3.3-rc10 branch (diydrones/ardupilot@f21fd6d61ea3844128cdfe8558bd7d93dc7bde66. This is one commit ahead of diydrones/ardupilot@bec4e436306691ad2514e27e69cfedec8e4105b2; the only difference is release notes, so there should be no functional change.).

However, it does look like sending SetYaw with is_relative is somewhat broken. As it keeps sending a SetYaw command frequently, it looks like ArduPilot doesn't like this, especially if the angle is large.

BrettRD commented 9 years ago

The flip back and forth was with "fc->fb->SetYaw(-90, false);" Sent every frame in the object tracker during a bug hunt. Given the issues in sending relative commands to an unknown control loop without saturating it, I'm keeping well away from relative yaw commands.