Set Front cam pitch the same as the drone pitch

Hi,
I want the front camera to always aim in front of the drone
I can’t move the front camera, it always aims at the same point in the ned basis
I tried to use the same method as in the hello drone mission but i did not succeed


Any ideas ?

Tanks!
Mel

Hi @MelP ,

Can you confirm that the code you provided is called in the generateAttitudeReferences() function of your mode ?

Also, can you confirm that the variable droneYaw you are using is fetched from the telemetry and is up to date before calling this code ?

Finally, could you describe exactly what is the drone behavior you are trying to achieve ?
You mentioned the drone pitch in the title but it seems that you have problems with the yaw, so I am a bit confused ^^" : do you want the front camera acting like it’s fixed relatively to the drone (i.e. yawing, pitching and rolling with the drone) or do you only want the camera yaw to follow the drone yaw for instance ?

Best,
Gauthier

Hi,

Yes the code is called in generateAttitudeReferences() and the variable droneYaw is fetched from the telemetry
I made mistakes in the title… :neutral_face:
I want the front camera camera acting like it’s fixes relatively to the drone

current unwanted behavior:
Peek 18-05-2022 11-18

Hi @MelP !

Thank you for the details and the video.

I guess the implementation of the setRotationVelocity is the one you shared in your previous post ? I think the problem is that your variable fcam_ref is not a pointer, and thus only modified within the scope of your function, can you confirm ?

Beside, if you want a fixed front camera, maybe you could try using the BASE frame of reference rather than the NED one. In that case you need to deactivate the filtering too :

guidance::Output *output = getOutput();

// set camera axes config
// locked to let the guidance mode control an axis
// smoothing deactivate to be compatible with the BASE vector basis
output->mHasFrontCamReferenceConfig = true;

output->mFrontCamReferenceConfig.mutable_yaw()->set_locked(true);
output->mFrontCamReferenceConfig.mutable_yaw()->set_filtered(false);

output->mFrontCamReferenceConfig.mutable_pitch()->set_locked(true);
output->mFrontCamReferenceConfig.mutable_pitch()->set_filtered(false);

output->mFrontCamReferenceConfig.mutable_roll()->set_locked(true);
output->mFrontCamReferenceConfig.mutable_roll()->set_filtered(false);

// set axes references : you want the same orientation as the base (drone)
// so the reference is ... 0 for each axis in this base :p
output->mHasFrontCamReference = true;

output->mFrontCamReference.mutable_yaw()->set_ctrl_mode(
	CamController::Messages::ControlMode::POSITION);
output->mFrontCamReference.mutable_yaw()->set_frame_of_ref(
	CamController::Messages::FrameOfReference::BASE);
output->mFrontCamReference.mutable_yaw()->set_position(0.f);

output->mFrontCamReference.mutable_pitch()->set_ctrl_mode(
	CamController::Messages::ControlMode::POSITION);
output->mFrontCamReference.mutable_pitch()->set_frame_of_ref(
	CamController::Messages::FrameOfReference::BASE);
output->mFrontCamReference.mutable_pitch()->set_position(0.f);

output->mFrontCamReference.mutable_roll()->set_ctrl_mode(
	CamController::Messages::ControlMode::POSITION);
output->mFrontCamReference.mutable_roll()->set_frame_of_ref(
	CamController::Messages::FrameOfReference::BASE);
output->mFrontCamReference.mutable_roll()->set_position(0.f);

Best,
Gauthier

1 Like

The variable fcam_ref was the problem, thanks for all the explanations I understand better how it works now !

This topic was automatically closed 3 days after the last reply. New replies are no longer allowed.