Skip to content

[WIP]Feature/pixy parser#43

Open
Aksellence wants to merge 32 commits intomaster-0.4from
feature/pixy_parser
Open

[WIP]Feature/pixy parser#43
Aksellence wants to merge 32 commits intomaster-0.4from
feature/pixy_parser

Conversation

@Aksellence
Copy link
Contributor

No description provided.

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

quite difficult to review unfortunately. I've done a first pass, but really needs some cleanup to make the code clearer

}
}

bool AC_PrecLand::target_acquired()
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it's best not to change formatting for no reason. Also please follow the ArduPilot style guide.
http://ardupilot.org/dev/docs/style-guide.html

return _target_acquired;
}

void AC_PrecLand::set_target_acquired(bool _target_acquired_value) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why use an _ prefix on the variable name for a function?
(some people like _ for private variables in classes, which is fine if you like it, but pointless for local variables)

public:
// Constructor
AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) :
AC_PrecLand_Backend(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) :
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why remove the const? Better to expose the data you want in the state struct


protected:
const AC_PrecLand& _frontend; // reference to precision landing front end
AC_PrecLand& _frontend; // reference to precision landing front end
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should leave const alone

irlock(),
_have_los_meas(false),
_los_meas_time_ms(0)
_los_meas_time_ms(0),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we don't actually need to initialise values to 0 or false, as it happens automatically (as we override memory allocation with a function that zeros memory)

} irlock_target_info;

irlock_target_info _target_info;
irlock_target_info _target_info[10];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this looks like the source for the magic 10 above


irlock_target_info _target_info;
irlock_target_info _target_info[10];
size_t _num_targets;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why size_t?

You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is this parser code from another project, or is it new code?
If from an existing project then we should refer to that project and give credit

#include <string.h>

#define PIXY_PARSER_PIXY_BUF_SIZE 17
#define PIXY_PARSER_MAX_BLOBS 10
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe this is the magic 10?


if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes
pixy_len--; ///----------------------------------------QUES----------------------------------------------
memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i don't understand how this works. Looks like a byte array, so this shifts by one byte, but comment implies its a block?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants