Skip to content

Commit

Permalink
updated for the new mrs_modules_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Sep 30, 2023
1 parent cdc47b2 commit be032c1
Show file tree
Hide file tree
Showing 13 changed files with 94 additions and 92 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ set(CATKIN_DEPENDENCIES
nodelet
sensor_msgs
mrs_msgs
mrs_modules_msgs
std_msgs
mrs_lib
dynamic_reconfigure
Expand Down
5 changes: 3 additions & 2 deletions include/gimbal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@
#include <mutex>
#include <string>

#include <mrs_msgs/GimbalPRY.h>
#include <mrs_modules_msgs/GimbalPRY.h>

#include <dynamic_reconfigure/server.h>
#include "SBGC_lib/SBGC.h"
#include "serial_port.h"
Expand Down Expand Up @@ -86,7 +87,7 @@ namespace gimbal {

void cmd_orientation_cbk(const geometry_msgs::QuaternionStamped::ConstPtr &cmd_orientation);

void cmd_pry_cbk(const mrs_msgs::GimbalPRY::ConstPtr &cmd_pry);
void cmd_pry_cbk(const mrs_modules_msgs::GimbalPRY::ConstPtr &cmd_pry);

bool rotate_gimbal_PRY(double pitch, double roll, double yaw);

Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>mrs_msgs</depend>
<depend>mrs_modules_msgs</depend>
<depend>mrs_lib</depend>
<depend>dynamic_reconfigure</depend>

Expand Down
16 changes: 8 additions & 8 deletions src/baca_protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include <mutex>

#include <string>
#include <mrs_msgs/BacaProtocol.h>
#include <mrs_msgs/SerialRaw.h>
#include <mrs_modules_msgs/BacaProtocol.h>
#include <mrs_modules_msgs/SerialRaw.h>
#include <mrs_msgs/SetInt.h>

#include <serial_port.h>
Expand Down Expand Up @@ -62,8 +62,8 @@ class BacaProtocol : public nodelet::Nodelet {
bool callbackNetgunSafe(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
bool callbackNetgunArm(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
bool callbackNetgunFire(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
void callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg);
void callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg);
void callbackSendMessage(const mrs_modules_msgs::BacaProtocolConstPtr &msg);
void callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg);
void callbackMagnet(const std_msgs::EmptyConstPtr &msg);

bool callbackSendInt([[maybe_unused]] mrs_msgs::SetInt::Request &req, mrs_msgs::SetInt::Response &res);
Expand Down Expand Up @@ -146,7 +146,7 @@ void BacaProtocol::onInit() {
garmin_A_frame_ = uav_name_ + "/garmin" + postfix_A;
garmin_B_frame_ = uav_name_ + "/garmin" + postfix_B;

baca_protocol_publisher_ = nh_.advertise<mrs_msgs::BacaProtocol>("baca_protocol_out", 1);
baca_protocol_publisher_ = nh_.advertise<mrs_modules_msgs::BacaProtocol>("baca_protocol_out", 1);

baca_protocol_subscriber = nh_.subscribe("baca_protocol_in", 10, &BacaProtocol::callbackSendMessage, this, ros::TransportHints().tcpNoDelay());

Expand Down Expand Up @@ -251,7 +251,7 @@ void BacaProtocol::callbackMaintainerTimer(const ros::TimerEvent &event) {

/* callbackSendMessage() //{ */

void BacaProtocol::callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg) {
void BacaProtocol::callbackSendMessage(const mrs_modules_msgs::BacaProtocolConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -284,7 +284,7 @@ void BacaProtocol::callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg

/* callbackSendRawMessage() //{ */

void BacaProtocol::callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg) {
void BacaProtocol::callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -484,7 +484,7 @@ void BacaProtocol::processMessage(uint8_t payload_size, uint8_t *input_buffer, u
if (checksum_correct) {
received_msg_ok++;
}
mrs_msgs::BacaProtocol msg;
mrs_modules_msgs::BacaProtocol msg;
msg.stamp = ros::Time::now();
for (uint8_t i = 0; i < payload_size; i++) {
msg.payload.push_back(input_buffer[i]);
Expand Down
16 changes: 8 additions & 8 deletions src/eagle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include <mutex>

#include <string>
#include <mrs_msgs/BacaProtocol.h>
#include <mrs_msgs/SerialRaw.h>
#include <mrs_modules_msgs/BacaProtocol.h>
#include <mrs_modules_msgs/SerialRaw.h>
#include <mrs_msgs/SetInt.h>

#include <serial_port.h>
Expand Down Expand Up @@ -67,8 +67,8 @@ class Eagle : public nodelet::Nodelet {
bool callbackNetgunSafe(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
bool callbackNetgunArm(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
bool callbackNetgunFire(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
void callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg);
void callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg);
void callbackSendMessage(const mrs_modules_msgs::BacaProtocolConstPtr &msg);
void callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg);
void callbackMagnet(const std_msgs::EmptyConstPtr &msg);

bool callbackSendInt([[maybe_unused]] mrs_msgs::SetInt::Request &req, mrs_msgs::SetInt::Response &res);
Expand Down Expand Up @@ -160,7 +160,7 @@ void Eagle::onInit() {
garmin_A_frame_ = uav_name_ + "/garmin" + postfix_A;
garmin_B_frame_ = uav_name_ + "/garmin" + postfix_B;

eagle_publisher_ = nh_.advertise<mrs_msgs::BacaProtocol>("eagle_out", 1);
eagle_publisher_ = nh_.advertise<mrs_modules_msgs::BacaProtocol>("eagle_out", 1);

eagle_subscriber = nh_.subscribe("eagle_in", 10, &Eagle::callbackSendMessage, this, ros::TransportHints().tcpNoDelay());

Expand Down Expand Up @@ -265,7 +265,7 @@ void Eagle::callbackMaintainerTimer(const ros::TimerEvent &event) {

/* callbackSendMessage() //{ */

void Eagle::callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg) {
void Eagle::callbackSendMessage(const mrs_modules_msgs::BacaProtocolConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -298,7 +298,7 @@ void Eagle::callbackSendMessage(const mrs_msgs::BacaProtocolConstPtr &msg) {

/* callbackSendRawMessage() //{ */

void Eagle::callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg) {
void Eagle::callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -606,7 +606,7 @@ void Eagle::processMessage(uint8_t payload_size, uint8_t *input_buffer, uint8_t
if (checksum_correct) {
received_msg_ok++;
}
mrs_msgs::BacaProtocol msg;
mrs_modules_msgs::BacaProtocol msg;
msg.stamp = ros::Time::now();
for (uint8_t i = 0; i < payload_size; i++) {
msg.payload.push_back(input_buffer[i]);
Expand Down
16 changes: 8 additions & 8 deletions src/estop.cpp
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
#include "mrs_msgs/SetIntRequest.h"
#include "mrs_msgs/SetIntResponse.h"
#include <ros/package.h>
#include <stdlib.h>
#include <ros/ros.h>
#include <sensor_msgs/Range.h>
#include <std_msgs/Char.h>
#include <std_srvs/SetBool.h>
#include <std_srvs/Trigger.h>
#include <mrs_msgs/SetInt.h>
#include <std_msgs/Empty.h>
#include <mutex>

#include <string>
#include <mrs_msgs/BacaProtocol.h>

#include <mrs_modules_msgs/BacaProtocol.h>
#include <mrs_modules_msgs/SerialRaw.h>

#include <mrs_msgs/SetInt.h>
#include <mrs_msgs/ControlManagerDiagnostics.h>
#include <mrs_msgs/SerialRaw.h>

#include <mrs_lib/param_loader.h>
#include <mrs_lib/service_client_handler.h>
Expand Down Expand Up @@ -67,7 +67,7 @@ class Estop : public nodelet::Nodelet {
void callbackEstopTimer(const ros::TimerEvent &event);
void callbackMaintainerTimer(const ros::TimerEvent &event);

void callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg);
void callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg);
void controlManagerCallback(const mrs_msgs::ControlManagerDiagnosticsConstPtr &msg);

uint8_t connectToSensor(void);
Expand Down Expand Up @@ -311,7 +311,7 @@ void Estop::callbackMaintainerTimer(const ros::TimerEvent &event) {

/* callbackSendRawMessage() //{ */

void Estop::callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg) {
void Estop::callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -426,7 +426,7 @@ void Estop::processMessage(uint8_t payload_size, uint8_t *input_buffer, uint8_t
if (checksum_correct) {
received_msg_ok++;
}
mrs_msgs::BacaProtocol msg;
mrs_modules_msgs::BacaProtocol msg;
msg.stamp = ros::Time::now();
for (uint8_t i = 0; i < payload_size; i++) {
msg.payload.push_back(input_buffer[i]);
Expand Down
6 changes: 3 additions & 3 deletions src/gimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace gimbal
m_pub_attitude = m_nh.advertise<nav_msgs::Odometry>("attitude_out", 10);
m_pub_speed = m_nh.advertise<geometry_msgs::Vector3>("speed_out", 10);
m_pub_command = m_nh.advertise<nav_msgs::Odometry>("current_setpoint", 10);
m_pub_orientation_pry = m_nh.advertise<mrs_msgs::GimbalPRY>("attitude_out_pry", 10);
m_pub_orientation_pry = m_nh.advertise<mrs_modules_msgs::GimbalPRY>("attitude_out_pry", 10);

m_sub_attitude = m_nh.subscribe("attitude_in", 10, &Gimbal::attitude_cbk, this);
m_sub_command = m_nh.subscribe("cmd_orientation", 10, &Gimbal::cmd_orientation_cbk, this);
Expand Down Expand Up @@ -234,7 +234,7 @@ namespace gimbal
//}

/* cmd_pry_cbk() method //{ */
void Gimbal::cmd_pry_cbk(const mrs_msgs::GimbalPRY::ConstPtr &cmd_pry) {
void Gimbal::cmd_pry_cbk(const mrs_modules_msgs::GimbalPRY::ConstPtr &cmd_pry) {
rotate_gimbal_PRY_between_frames(cmd_pry->pitch, cmd_pry->roll, cmd_pry->yaw,
m_base_frame_id, m_stabilization_frame_id);
}
Expand Down Expand Up @@ -276,7 +276,7 @@ namespace gimbal

/* Process the gimbal orientation frame //{ */
if (m_request_data_flags & cmd_realtime_data_custom_flags_stator_rotor_angle) {
auto msg_pry = boost::make_shared<mrs_msgs::GimbalPRY>();
auto msg_pry = boost::make_shared<mrs_modules_msgs::GimbalPRY>();

msg_pry->pitch = data.stator_rotor_angle[1];
msg_pry->roll = data.stator_rotor_angle[0];
Expand Down
21 changes: 10 additions & 11 deletions src/led.cpp
Original file line number Diff line number Diff line change
@@ -1,19 +1,18 @@
#include "mrs_msgs/SetIntRequest.h"
#include "mrs_msgs/SetIntResponse.h"
#include <ros/package.h>
#include <stdlib.h>
#include <ros/ros.h>
#include <sensor_msgs/Range.h>
#include <std_msgs/Char.h>
#include <std_srvs/SetBool.h>
#include <std_srvs/SetBool.h>
#include <mrs_msgs/SetInt.h>
#include <std_msgs/Empty.h>
#include <mutex>

#include <mrs_msgs/SetInt.h>

#include <string>
#include <mrs_msgs/BacaProtocol.h>
#include <mrs_msgs/SerialRaw.h>
#include <mrs_modules_msgs/BacaProtocol.h>
#include <mrs_modules_msgs/SerialRaw.h>

#include <serial_port.h>

Expand Down Expand Up @@ -59,7 +58,7 @@ class Led : public nodelet::Nodelet {
bool callbackLed(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
bool callbackOuster(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);

void callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg);
void callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg);

uint8_t connectToSensor(void);
void processMessage(uint8_t payload_size, uint8_t *input_buffer, uint8_t checksum, uint8_t checksum_rec, bool checksum_correct);
Expand Down Expand Up @@ -119,8 +118,8 @@ void Led::onInit() {
nh_.param("serial_buffer_size", serial_buffer_size_, 1024);

// Publishers
baca_protocol_publisher_ = nh_.advertise<mrs_msgs::BacaProtocol>("baca_protocol_out", 1);
/* baca_protocol_debug_publisher_ = nh_.advertise<mrs_msgs::BacaProtocol>("baca_protocol_out_debug", 1); */
baca_protocol_publisher_ = nh_.advertise<mrs_modules_msgs::BacaProtocol>("baca_protocol_out", 1);
/* baca_protocol_debug_publisher_ = nh_.advertise<mrs_modules_msgs::BacaProtocol>("baca_protocol_out_debug", 1); */

raw_message_subscriber = nh_.subscribe("raw_in", 10, &Led::callbackSendRawMessage, this, ros::TransportHints().tcpNoDelay());

Expand Down Expand Up @@ -206,7 +205,7 @@ void Led::callbackMaintainerTimer(const ros::TimerEvent &event) {

/* callbackSendRawMessage() //{ */

void Led::callbackSendRawMessage(const mrs_msgs::SerialRawConstPtr &msg) {
void Led::callbackSendRawMessage(const mrs_modules_msgs::SerialRawConstPtr &msg) {

if (!is_initialized_) {
return;
Expand Down Expand Up @@ -265,7 +264,7 @@ bool Led::callbackAll(std_srvs::SetBool::Request &req, std_srvs::SetBool::Respon

serial_port_.sendCharArray(out_buffer, payload_size + 3);

/* mrs_msgs::BacaProtocol msg; */
/* mrs_modules_msgs::BacaProtocol msg; */
/* msg.stamp = ros::Time::now(); */
/* for (uint8_t i = 0; i < payload_size + 3; i++) { */
/* msg.payload.push_back(out_buffer[i]); */
Expand Down Expand Up @@ -490,7 +489,7 @@ void Led::processMessage(uint8_t payload_size, uint8_t *input_buffer, uint8_t ch
if (checksum_correct) {
received_msg_ok++;
}
mrs_msgs::BacaProtocol msg;
mrs_modules_msgs::BacaProtocol msg;
msg.stamp = ros::Time::now();
for (uint8_t i = 0; i < payload_size; i++) {
msg.payload.push_back(input_buffer[i]);
Expand Down
34 changes: 17 additions & 17 deletions src/nmea_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,15 @@
#include <ros/ros.h>
#include <mutex>

#include <mrs_msgs/Gpgga.h>
#include <mrs_msgs/Gpgsa.h>
#include <mrs_msgs/Gpgst.h>
#include <mrs_msgs/Gpvtg.h>
#include <mrs_modules_msgs/Gpgga.h>
#include <mrs_modules_msgs/Gpgsa.h>
#include <mrs_modules_msgs/Gpgst.h>
#include <mrs_modules_msgs/Gpvtg.h>

#include <mrs_msgs/StringStamped.h>

#include <mrs_msgs/Bestpos.h>
#include <mrs_msgs/GpsStatus.h>
#include <mrs_modules_msgs/Bestpos.h>
#include <mrs_modules_msgs/GpsStatus.h>

#include <std_msgs/String.h>

Expand Down Expand Up @@ -86,7 +86,7 @@ class NmeaParser : public nodelet::Nodelet {
ros::Timer serial_timer_;
ros::Timer maintainer_timer_;

mrs_msgs::Bestpos bestpos_msg_;
mrs_modules_msgs::Bestpos bestpos_msg_;

serial_port::SerialPort serial_port_;

Expand Down Expand Up @@ -139,11 +139,11 @@ void NmeaParser::onInit() {
nh_.param("serial_rate", serial_rate_, 500);
nh_.param("serial_buffer_size", serial_buffer_size_, 1024);

gpgga_pub_ = nh_.advertise<mrs_msgs::Gpgga>("gpgga_out", 1);
gpgsa_pub_ = nh_.advertise<mrs_msgs::Gpgsa>("gpgsa_out", 1);
gpgst_pub_ = nh_.advertise<mrs_msgs::Gpgst>("gpgst_out", 1);
gpvtg_pub_ = nh_.advertise<mrs_msgs::Gpvtg>("gpvtg_out", 1);
bestpos_pub_ = nh_.advertise<mrs_msgs::Bestpos>("bestpos_out", 1);
gpgga_pub_ = nh_.advertise<mrs_modules_msgs::Gpgga>("gpgga_out", 1);
gpgsa_pub_ = nh_.advertise<mrs_modules_msgs::Gpgsa>("gpgsa_out", 1);
gpgst_pub_ = nh_.advertise<mrs_modules_msgs::Gpgst>("gpgst_out", 1);
gpvtg_pub_ = nh_.advertise<mrs_modules_msgs::Gpvtg>("gpvtg_out", 1);
bestpos_pub_ = nh_.advertise<mrs_modules_msgs::Bestpos>("bestpos_out", 1);
string_pub_ = nh_.advertise<std_msgs::String>("status_out", 1);
string_raw_pub_ = nh_.advertise<mrs_msgs::StringStamped>("raw_out", 1);

Expand Down Expand Up @@ -304,8 +304,8 @@ void NmeaParser::processMessage() {

void NmeaParser::processGPGGA(std::vector<std::string>& results) {

mrs_msgs::Gpgga gpgga_msg;
mrs_msgs::GpsStatus gps_status;
mrs_modules_msgs::Gpgga gpgga_msg;
mrs_modules_msgs::GpsStatus gps_status;

/* for (size_t i = 0; i < results.size(); i++) { */
/* ROS_INFO_STREAM("[NmeaParser]: " << i << " " << results[i]); */
Expand Down Expand Up @@ -440,7 +440,7 @@ void NmeaParser::processGPGGA(std::vector<std::string>& results) {

void NmeaParser::processGPGSA(std::vector<std::string>& results) {

mrs_msgs::Gpgsa gpgsa_msg;
mrs_modules_msgs::Gpgsa gpgsa_msg;
gpgsa_msg.header.stamp = ros::Time::now();

gpgsa_msg.auto_manual_mode = results[2];
Expand Down Expand Up @@ -475,7 +475,7 @@ void NmeaParser::processGPGSA(std::vector<std::string>& results) {

void NmeaParser::processGPGST(std::vector<std::string>& results) {

mrs_msgs::Gpgst gpgst_msg;
mrs_modules_msgs::Gpgst gpgst_msg;
gpgst_msg.header.stamp = ros::Time::now();

/* for (size_t i = 0; i < results.size(); i++) { */
Expand Down Expand Up @@ -510,7 +510,7 @@ void NmeaParser::processGPGST(std::vector<std::string>& results) {

void NmeaParser::processGPVTG(std::vector<std::string>& results) {

mrs_msgs::Gpvtg gpvtg_msg;
mrs_modules_msgs::Gpvtg gpvtg_msg;
gpvtg_msg.header.stamp = ros::Time::now();

/* for (size_t i = 0; i < results.size(); i++) { */
Expand Down
Loading

0 comments on commit be032c1

Please sign in to comment.