cleanup: use const for struct Location pointers and references

this allows the compiler to generate more efficient code
This commit is contained in:
tobias 2013-03-26 12:58:54 +01:00 committed by Andrew Tridgell
parent 6516bffbb6
commit 217b8d7a59
19 changed files with 35 additions and 34 deletions

View File

@ -300,7 +300,7 @@ struct log_Cmd {
};
// Write a command processing packet. Total length : 19 bytes
static void Log_Write_Cmd(uint8_t num, struct Location *wp)
static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
{
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
@ -655,7 +655,7 @@ static void log_callback(uint8_t msgid)
// dummy functions
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Startup(uint8_t type) {}
static void Log_Write_Cmd(uint8_t num, struct Location *wp) {}
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) {}
static void Log_Write_Current() {}
static void Log_Write_Nav_Tuning() {}
static void Log_Write_GPS( uint32_t log_Time, int32_t log_Lattitude, int32_t log_Longitude, int32_t log_gps_alt, int32_t log_mix_alt,

View File

@ -100,7 +100,7 @@ static void set_cmd_with_index(struct Location temp, int i)
This function stores waypoint commands
It looks to see what the next command type is and finds the last command.
*/
static void set_next_WP(struct Location *wp)
static void set_next_WP(const struct Location *wp)
{
// copy the current WP into the OldWP slot
// ---------------------------------------

View File

@ -304,7 +304,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
}
static void
test_wp_print(struct Location *cmd, uint8_t wp_index)
test_wp_print(const struct Location *cmd, uint8_t wp_index)
{
cliSerial->printf_P(PSTR("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
(int)wp_index,

View File

@ -685,7 +685,7 @@ struct log_Cmd {
};
// Write a command processing packet. Total length : 21 bytes
static void Log_Write_Cmd(uint8_t num, struct Location *wp)
static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
{
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
@ -1354,7 +1354,7 @@ static void log_callback(uint8_t msgid)
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) {}
static void Log_Write_Startup() {}
static void Log_Write_Cmd(uint8_t num, struct Location *wp) {}
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) {}
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_IMU() {}
static void Log_Write_GPS() {}

View File

@ -124,7 +124,7 @@ static int32_t get_RTL_alt()
* It precalculates all the necessary stuff.
*/
static void set_next_WP(struct Location *wp)
static void set_next_WP(const struct Location *wp)
{
// copy the current WP into the OldWP slot
// ---------------------------------------

View File

@ -1416,7 +1416,7 @@ init_esc()
}
}
static void print_wp(struct Location *cmd, uint8_t index)
static void print_wp(const struct Location *cmd, uint8_t index)
{
//float t1 = (float)cmd->lat / t7;
//float t2 = (float)cmd->lng / t7;

View File

@ -298,7 +298,7 @@ struct log_Cmd {
};
// Write a command processing packet. Total length : 19 bytes
static void Log_Write_Cmd(uint8_t num, struct Location *wp)
static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
{
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
@ -702,7 +702,7 @@ static void log_callback(uint8_t msgid)
// dummy functions
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Startup(uint8_t type) {}
static void Log_Write_Cmd(uint8_t num, struct Location *wp) {}
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) {}
static void Log_Write_Current() {}
static void Log_Write_Nav_Tuning() {}
static void Log_Write_GPS() {}

View File

@ -147,7 +147,7 @@ static int32_t read_alt_to_hold()
* This function stores waypoint commands
* It looks to see what the next command type is and finds the last command.
*/
static void set_next_WP(struct Location *wp)
static void set_next_WP(const struct Location *wp)
{
// copy the current WP into the OldWP slot
// ---------------------------------------

View File

@ -263,7 +263,7 @@ static void do_land()
set_next_WP(&next_nav_command);
}
static void loiter_set_direction_wp(struct Location *nav_command)
static void loiter_set_direction_wp(const struct Location *nav_command)
{
if (nav_command->options & MASK_OPTIONS_LOITER_DIRECTION) {
loiter_direction = -1;

View File

@ -334,7 +334,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
}
static void
test_wp_print(struct Location *cmd, uint8_t wp_index)
test_wp_print(const struct Location *cmd, uint8_t wp_index)
{
cliSerial->printf_P(PSTR("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
(int)wp_index,

View File

@ -45,11 +45,12 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = {
AP_GROUPEND
};
AP_Limit_Altitude::AP_Limit_Altitude(struct Location *current_loc) :
AP_Limit_Module(AP_LIMITS_ALTITUDE) // enabled and required
AP_Limit_Altitude::AP_Limit_Altitude(const struct Location *current_loc) :
AP_Limit_Module(AP_LIMITS_ALTITUDE), // enabled and required
_current_loc(current_loc)
{
AP_Param::setup_object_defaults(this, var_info);
_current_loc = current_loc;
//_current_loc = current_loc;
}
bool AP_Limit_Altitude::triggered()

View File

@ -16,7 +16,7 @@
class AP_Limit_Altitude : public AP_Limit_Module {
public:
AP_Limit_Altitude(struct Location *current_loc);
AP_Limit_Altitude(const struct Location *current_loc);
AP_Int32 min_alt();
AP_Int32 max_alt();
@ -27,7 +27,7 @@ public:
static const struct AP_Param::GroupInfo var_info[];
protected:
struct Location * _current_loc;
const struct Location * _current_loc;
AP_Int32 _min_alt;
AP_Int32 _max_alt;

View File

@ -56,8 +56,8 @@ const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = {
AP_Limit_Geofence::AP_Limit_Geofence(uint16_t efs, uint8_t f_wp_s,
uint8_t max_fp, GPS *&gps, struct Location *h_loc,
struct Location *c_loc) :
uint8_t max_fp, GPS *&gps, const struct Location *h_loc,
const struct Location *c_loc) :
AP_Limit_Module(AP_LIMITS_GEOFENCE),
_gps(gps),
_current_loc(c_loc),

View File

@ -20,7 +20,7 @@
class AP_Limit_Geofence : public AP_Limit_Module {
public:
AP_Limit_Geofence(uint16_t eeprom_fence_start, uint8_t fpsize, uint8_t max_fp, GPS *&gps, struct Location *home_loc, struct Location *current_loc);
AP_Limit_Geofence(uint16_t eeprom_fence_start, uint8_t fpsize, uint8_t max_fp, GPS *&gps, const struct Location *home_loc, const struct Location *current_loc);
bool init();
bool triggered();
@ -38,8 +38,8 @@ protected:
// pointers to gps, current location and home
GPS *& _gps;
struct Location * _current_loc;
struct Location * _home;
const struct Location * _current_loc;
const struct Location * _home;
// Simple mode, just radius

View File

@ -70,9 +70,9 @@ int32_t get_bearing_cd(const struct Location *loc1, const struct
// our previous waypoint and point2 is our target waypoint
// then this function returns true if we have flown past
// the target waypoint
bool location_passed_point(struct Location & location,
struct Location & point1,
struct Location & point2);
bool location_passed_point(const struct Location & location,
const struct Location & point1,
const struct Location & point2);
// extrapolate latitude/longitude given bearing and distance
void location_update(struct Location *loc, float bearing, float distance);

View File

@ -64,7 +64,7 @@ static void test_passed_waypoint(void)
hal.console->println("waypoint tests OK");
}
static void test_one_offset(struct Location &loc,
static void test_one_offset(const struct Location &loc,
float ofs_north, float ofs_east,
float dist, float bearing)
{

View File

@ -72,9 +72,9 @@ int32_t get_bearing_cd(const struct Location *loc1, const struct Location *loc2)
// our previous waypoint and point2 is our target waypoint
// then this function returns true if we have flown past
// the target waypoint
bool location_passed_point(struct Location &location,
struct Location &point1,
struct Location &point2)
bool location_passed_point(const struct Location &location,
const struct Location &point1,
const struct Location &point2)
{
// the 3 points form a triangle. If the angle between lines
// point1->point2 and location->point2 is greater than 90

View File

@ -533,7 +533,7 @@ void AP_Mount::status_msg(mavlink_message_t *msg)
}
/// Set mount point/region of interest, triggered by mission script commands
void AP_Mount::set_roi_cmd(struct Location *target_loc)
void AP_Mount::set_roi_cmd(const struct Location *target_loc)
{
#if MNT_GPSPOINT_OPTION == ENABLED
// set the target gps location
@ -571,7 +571,7 @@ AP_Mount::angle_input_rad(RC_Channel* rc, int16_t angle_min, int16_t angle_max)
}
void
AP_Mount::calc_GPS_target_angle(struct Location *target)
AP_Mount::calc_GPS_target_angle(const struct Location *target)
{
float GPS_vector_x = (target->lng-_current_loc->lng)*cosf(ToRad((_current_loc->lat+target->lat)*0.00000005f))*0.01113195f;
float GPS_vector_y = (target->lat-_current_loc->lat)*0.01113195f;

View File

@ -46,7 +46,7 @@ public:
void configure_msg(mavlink_message_t* msg);
void control_msg(mavlink_message_t* msg);
void status_msg(mavlink_message_t* msg);
void set_roi_cmd(struct Location *target_loc);
void set_roi_cmd(const struct Location *target_loc);
void configure_cmd();
void control_cmd();
@ -72,7 +72,7 @@ private:
void set_GPS_target_location(Location targetGPSLocation); ///< used to tell the mount to track GPS location
// internal methods
void calc_GPS_target_angle(struct Location *target);
void calc_GPS_target_angle(const struct Location *target);
void stabilize();
int16_t closest_limit(int16_t angle, int16_t* angle_min, int16_t* angle_max);
void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max);