Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

VehicleInfo Plugin : Ability to request basic vehicle information from mavros #1147

Closed
wants to merge 1 commit into from

Conversation

Kiwa21
Copy link
Contributor

@Kiwa21 Kiwa21 commented Jan 1, 2019

As requested by the goodrobots projects by @fnoop : https://github.com/goodrobots

New plugin in mavros_extras with one new msg and 3 services.
Used to request information such as :
uint8_t autopilot = enum_value(MAV_AUTOPILOT::GENERIC); uint8_t type = enum_value(MAV_TYPE::GENERIC); uint8_t sysid = 0; uint8_t compid = 0; std::string mode = ""; uint32_t mode_id = 0; uint8_t system_status = enum_value(MAV_STATE::UNINIT); uint64_t capabilities = 0; uint32_t flight_sw_version = 0; uint32_t middleware_sw_version = 0; uint32_t os_sw_version = 0; uint32_t board_version = 0; uint16_t vendor_id = 0; uint16_t product_id = 0; uint64_t uid = 0;

Open to all suggestions :)
Thanks,

Copy link
Member

@TSC21 TSC21 left a comment

Choose a reason for hiding this comment

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

I don't see any advantages on adding a new plugin for this same purpose - an extension to sys_status is more adequate on this sense.

@Kiwa21
Copy link
Contributor Author

Kiwa21 commented Jan 1, 2019

I didn't want to mess into the sys_status plugin because I thought that was an "extra" plugin only certains pple would enable.
I can do a new PR modifying sys_status and just adding the VehicleInfo msg and callback into it if you prefer!
Are you ok with the rest though ? Vehicle struct and msg ?

@TSC21
Copy link
Member

TSC21 commented Jan 1, 2019

Yes I am ok with the rest but by far the best way would be extending the existing sys_status plugin for the simple fact that all the cb you need are there.

};

VehicleInfo my_vehicle;
std::vector<VehicleInfo> vehicles;
Copy link
Member

Choose a reason for hiding this comment

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

In that situation it's better to use std::unordered_map<uint16_t,VehicleInfo>
Where uint16_t key = sysid << 8 | compid; (make inline helper).

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Agreed ! Fixed

uint8_t sysid = 0;
uint8_t compid = 0;
std::string mode = "";
uint32_t mode_id = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Better to store both: base_mode and custom_mode;

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added base_mode and custom_mode as well as retaining string and id for clarity

}

new_vehicle.system_status = hb.system_status;
vehicles.push_back(new_vehicle);
Copy link
Member

Choose a reason for hiding this comment

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

Nonono! Use emplace_back()

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thanks ! Always used push_back, I guess I was wrong !
Fixed

new_vehicle.product_id = apv.product_id;
new_vehicle.uid = apv.uid;

vehicles.push_back(new_vehicle);
Copy link
Member

Choose a reason for hiding this comment

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

Also note that you can avoid doubling of assigns by following:

iterator it;

it = vehicles.find(key);
if (!it) {
    auto res = vehicles.emplace(key, ...);
    it = res.first;
}

ROS_ASSERT(it);

it->sysid = sysid;
...

@@ -0,0 +1,17 @@
# Vehicle Info msg
std_msgs/Header header
Copy link
Member

Choose a reason for hiding this comment

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

It is not necessary in that case.

# Request a specific Vehicle Info by sysid/compid

uint8_t sysid
uint8_t compid
Copy link
Member

Choose a reason for hiding this comment

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

I think you can merge all get calls into one:

uint8 GET_MY_SYSID = 0
uint8 GET_MY_COMPID = 0

uint8 sysid
uint8 compid
bool get_all
---
bool success
mavros_msgs/VehicleInfo[] vehicles

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Done :)

@Kiwa21
Copy link
Contributor Author

Kiwa21 commented Jan 2, 2019

Took all comments into consideration and opened a new PR with all of this in the sys_status plugin : #1150

@Kiwa21 Kiwa21 closed this Jan 2, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants