mirror of https://github.com/ArduPilot/ardupilot
fixed some compiler warnings
the junk variables are not needed git-svn-id: https://arducopter.googlecode.com/svn/trunk@3249 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
89f9fafb90
commit
fe05603582
|
@ -455,15 +455,15 @@ init_compass()
|
||||||
{
|
{
|
||||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||||
dcm.set_compass(&compass);
|
dcm.set_compass(&compass);
|
||||||
bool junkbool = compass.init();
|
compass.init();
|
||||||
Vector3f junkvector = compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef OPTFLOW_ENABLED
|
#ifdef OPTFLOW_ENABLED
|
||||||
static void
|
static void
|
||||||
init_optflow()
|
init_optflow()
|
||||||
{
|
{
|
||||||
bool junkbool = optflow.init();
|
optflow.init();
|
||||||
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
|
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
|
||||||
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
|
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue