Skip to content
This repository has been archived by the owner on Feb 19, 2021. It is now read-only.

Change System ID and Component ID defaults and update logic #166

Merged
merged 4 commits into from
Apr 23, 2018

Conversation

lbegani
Copy link

@lbegani lbegani commented Apr 19, 2018

The changes are to update the system id and component id defaults and update logic to fix following issues -

  1. Handling of system ID: default, from conf file or from autopilot #149
  2. Support 6 cameras #142

lbegani added 2 commits April 19, 2018 08:41
Following is the logic:
    1. Read ID from the conf file
	( 1<id<255 : use as it is, do not read from vehicle
	  id<=0 or id>=255 : use 1 till read from vehicle)
    2. If conf file is not there, use default value 1 till valid ID read
       from vehicle
    3. If ID has to be read from vehicle,
	a. Start sending camera heartbeat with default system ID 1
    	b. On receiving autopilot heartbeat, send camera heartbeat with
           updated system ID.
    	c. On receiving heartbeats from multiple autopilots, stick to the
           first one
When running CSD with gazebo, default is set to MAV_COMP_ID_CAMERA2 to avoid
clash with Gazebo Camera running with PX4-SITL. When running without gazebo,
default can be set to MAV_COMP_ID_CAMERA.
@lbegani
Copy link
Author

lbegani commented Apr 19, 2018

@hamishwillee @shakthi-prashanth-m Kindly review

@lbegani lbegani changed the title Systemid compid Change System ID and Component ID defaults and update logic Apr 19, 2018
Copy link
Contributor

@hamishwillee hamishwillee left a comment

Choose a reason for hiding this comment

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

This looks good to me "by inspection". If you have tested it then happy for it to be merged.

Copy link

@shakthi-prashanth-m shakthi-prashanth-m left a comment

Choose a reason for hiding this comment

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

I added few comments. Please check.

@@ -68,20 +68,17 @@ MavlinkServer::MavlinkServer(const ConfFile &conf, std::vector<std::unique_ptr<S
_broadcast_addr.sin_port = htons(DEFAULT_MAVLINK_PORT);

Choose a reason for hiding this comment

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

Wrong Indentation

if (heartbeat.autopilot == 12)
_system_id = msg->sysid;

if (heartbeat.autopilot == 12) {

Choose a reason for hiding this comment

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

It's highly recommended to use the corresponding macro over a literal.

Copy link
Author

Choose a reason for hiding this comment

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

Fixed.

log_error("Invalid System ID for MAVLink communication (%d)", opt.sysid);
log_info("Use System ID 1, till heartbeat received from Vehicle");
_system_id = 1;
_is_sys_id_found = false;

Choose a reason for hiding this comment

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

It was false to to start with, isn't it ?

Copy link
Author

Choose a reason for hiding this comment

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

Fixed.

compid = MAV_COMP_ID_CAMERA;
#endif

while (compid < MAV_COMP_ID_CAMERA6 + 1) {

Choose a reason for hiding this comment

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

I think, while (compid <= MAV_COMP_ID_CAMERA6) is better in readability.

Copy link
Author

Choose a reason for hiding this comment

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

Fixed.

, _system_id(-1)
, _comp_id(MAV_COMP_ID_CAMERA2)
, _is_sys_id_found(false)
, _system_id(1)

Choose a reason for hiding this comment

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

A const initializer for default system ID would be better.

Copy link
Author

Choose a reason for hiding this comment

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

Fixed.

, _comp_id(MAV_COMP_ID_CAMERA2)
, _is_sys_id_found(false)
, _system_id(1)
, _comp_id(MAV_COMP_ID_CAMERA)

Choose a reason for hiding this comment

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

Do you initialize this in cases with or without Gazebo ?

Copy link
Author

@lbegani lbegani Apr 23, 2018

Choose a reason for hiding this comment

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

This is an unused variable, need to be removed later

Copy link

@shakthi-prashanth-m shakthi-prashanth-m left a comment

Choose a reason for hiding this comment

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

Looks good, except a minor comment.

@@ -75,10 +76,11 @@ MavlinkServer::MavlinkServer(const ConfFile &conf, std::vector<std::unique_ptr<S

} else {
log_error("Invalid System ID for MAVLink communication (%d)", opt.sysid);
log_info("Use System ID 1, till heartbeat received from Vehicle");
log_info("Use System ID %d, till heartbeat received from Vehicle", DEFAULT_SYSTEM_ID);
_system_id = 1;

Choose a reason for hiding this comment

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

Shouldn't this be

_system_id = DEFAULT_SYSTEM_ID;

Copy link
Author

Choose a reason for hiding this comment

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

Fixed.

@lbegani lbegani merged commit 8862156 into Dronecode:master Apr 23, 2018
@lbegani lbegani deleted the systemid-compid branch April 23, 2018 10:11
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants