Global: Fix typos

This commit is contained in:
Matthew Brener 2016-09-17 11:43:32 +10:00 committed by Lucas De Marchi
parent a4c1bc3fd3
commit 06388b0417
11 changed files with 11 additions and 11 deletions

View File

@ -523,7 +523,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
switch (msg->msgid) { switch (msg->msgid) {
// If we are currently operating as a proxy for a remote, // If we are currently operating as a proxy for a remote,
// alas we have to look inside each packet to see if its for us or for the remote // alas we have to look inside each packet to see if it's for us or for the remote
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
{ {
handle_request_data_stream(msg, false); handle_request_data_stream(msg, false);

View File

@ -461,7 +461,7 @@ uint32_t count = 0;
#else #else
data = pgm_read_word_near(0); //* get the first word of the user program data = pgm_read_word_near(0); //* get the first word of the user program
#endif #endif
if (data != 0xffff) //* make sure its valid before jumping to it. if (data != 0xffff) //* make sure it's valid before jumping to it.
{ {
asm volatile( asm volatile(
"clr r30 \n\t" "clr r30 \n\t"

View File

@ -584,7 +584,7 @@ else
-- intervalometer timing -- intervalometer timing
next_shot_time = next_shot_time + interval next_shot_time = next_shot_time + interval
-- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure its set right) -- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure it's set right)
if (focus_mode > 0) then if (focus_mode > 0) then
set_focus(infx) set_focus(infx)
sleep(100) sleep(100)

View File

@ -583,7 +583,7 @@ else
-- intervalometer timing -- intervalometer timing
next_shot_time = next_shot_time + interval next_shot_time = next_shot_time + interval
-- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure its set right) -- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure it's set right)
if (focus_mode > 0) then if (focus_mode > 0) then
set_focus(infx) set_focus(infx)
sleep(100) sleep(100)

View File

@ -555,7 +555,7 @@ else
-- intervalometer timing -- intervalometer timing
next_shot_time = next_shot_time + interval next_shot_time = next_shot_time + interval
-- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure its set right) -- set focus at infinity ? (maybe redundant for AFL & MF mode but makes sure it's set right)
if (focus_mode > 0) then if (focus_mode > 0) then
set_focus(infx) set_focus(infx)
sleep(100) sleep(100)

View File

@ -239,7 +239,7 @@ bool AP_Arming::ins_checks(bool report)
// get next gyro vector // get next gyro vector
const Vector3f &gyro_vec = ins.get_gyro(i); const Vector3f &gyro_vec = ins.get_gyro(i);
Vector3f vec_diff = gyro_vec - prime_gyro_vec; Vector3f vec_diff = gyro_vec - prime_gyro_vec;
// allow for up to 5 degrees/s difference. Pass if its // allow for up to 5 degrees/s difference. Pass if it has
// been OK in last 10 seconds // been OK in last 10 seconds
if (vec_diff.length() <= radians(5)) { if (vec_diff.length() <= radians(5)) {
last_gyro_pass_ms[i] = AP_HAL::millis(); last_gyro_pass_ms[i] = AP_HAL::millis();

View File

@ -319,7 +319,7 @@ AP_GPS::detect_instance(uint8_t instance)
new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]); new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]);
} }
// user has to explicitly set the MAV type, do not use AUTO // user has to explicitly set the MAV type, do not use AUTO
// Do not try to detect the MAV type, assume its there // Do not try to detect the MAV type, assume it's there
else if (_type[instance] == GPS_TYPE_MAV) { else if (_type[instance] == GPS_TYPE_MAV) {
_broadcast_gps_type("MAV", instance, dstate->last_baud); _broadcast_gps_type("MAV", instance, dstate->last_baud);
new_gps = new AP_GPS_MAV(*this, state[instance], NULL); new_gps = new AP_GPS_MAV(*this, state[instance], NULL);

View File

@ -2,7 +2,7 @@
* C preprocesor enumeration of the boards supported by the AP_HAL. * C preprocesor enumeration of the boards supported by the AP_HAL.
* This list exists so HAL_BOARD == HAL_BOARD_xxx preprocessor blocks * This list exists so HAL_BOARD == HAL_BOARD_xxx preprocessor blocks
* can be used to exclude HAL boards from the build when appropriate. * can be used to exclude HAL boards from the build when appropriate.
* Its not an elegant solution but we can improve it in future. * It's not an elegant solution but we can improve it in future.
*/ */
#pragma once #pragma once

View File

@ -10,7 +10,7 @@ public:
/** /**
* Call init from the platform hal instance init, so that both the type of * Call init from the platform hal instance init, so that both the type of
* the RCInput implementation and init argument (e.g. ISRRegistry) are * the RCInput implementation and init argument (e.g. ISRRegistry) are
* known to the programmer. (Its too difficult to describe this dependency * known to the programmer. (It's too difficult to describe this dependency
* in the C++ type system.) * in the C++ type system.)
*/ */
virtual void init() = 0; virtual void init() = 0;

View File

@ -45,7 +45,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac
// see if we are waiting for disk read // see if we are waiting for disk read
if (gcache.state == GRID_CACHE_DISKWAIT) { if (gcache.state == GRID_CACHE_DISKWAIT) {
// don't request data from the GCS till we know its not on disk // don't request data from the GCS till we know it's not on disk
return false; return false;
} }

View File

@ -936,7 +936,7 @@ void GCS_MAVLINK::send_message(enum ap_message id)
// this message id might already be deferred // this message id might already be deferred
for (i=0, nextid = next_deferred_message; i < num_deferred_messages; i++) { for (i=0, nextid = next_deferred_message; i < num_deferred_messages; i++) {
if (deferred_messages[nextid] == id) { if (deferred_messages[nextid] == id) {
// its already deferred, discard // it's already deferred, discard
return; return;
} }
nextid++; nextid++;