Skip to content

Commit

Permalink
updates to the mrs_status msg
Browse files Browse the repository at this point in the history
  • Loading branch information
DanHert committed Nov 24, 2023
1 parent 0d53f04 commit 769d066
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 24 deletions.
2 changes: 0 additions & 2 deletions launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,7 @@
<remap from="~throttle_in" to="control_manager/throttle" />
<remap from="~mass_estimate_in" to="control_manager/mass_estimate" />
<remap from="~mag_in" to="hw_api/magnetic_field" />

<remap from="~string_in" to="mrs_uav_status/display_string" />
<remap from="~set_service_in" to="mrs_uav_status/set_trigger_service" />

<!-- Publishers -->
<remap from="~uav_status_out" to="mrs_uav_status/uav_status" />
Expand Down
21 changes: 0 additions & 21 deletions src/data_acquisition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,6 @@ class Acquisition {
void gainManagerCallback(const mrs_msgs::GainManagerDiagnosticsConstPtr& msg);
void constraintManagerCallback(const mrs_msgs::ConstraintManagerDiagnosticsConstPtr& msg);
void stringCallback(const ros::MessageEvent<std_msgs::String const>& event);
void setServiceCallback(const std_msgs::String& msg);
void tfStaticCallback(const tf2_msgs::TFMessage& msg);
void hwApiGnssCallback(const sensor_msgs::NavSatFixConstPtr& msg);
void hwApiOdometryCallback(const nav_msgs::OdometryConstPtr& msg);
Expand Down Expand Up @@ -338,7 +337,6 @@ Acquisition::Acquisition() {
constraint_manager_subscriber_ =
nh_.subscribe("constraint_manager_in", 10, &Acquisition::constraintManagerCallback, this, ros::TransportHints().tcpNoDelay());
string_subscriber_ = nh_.subscribe("string_in", 10, &Acquisition::stringCallback, this, ros::TransportHints().tcpNoDelay());
set_service_subscriber_ = nh_.subscribe("set_service_in", 10, &Acquisition::setServiceCallback, this, ros::TransportHints().tcpNoDelay());
tf_static_subscriber_ = nh_.subscribe("tf_static_in", 100, &Acquisition::tfStaticCallback, this, ros::TransportHints().tcpNoDelay());
hw_api_odometry_subscriber_ = nh_.subscribe("odometry_in", 10, &Acquisition::hwApiOdometryCallback, this, ros::TransportHints().tcpNoDelay());
automatic_start_subscriber_ = nh_.subscribe("automatic_start_in", 10, &Acquisition::automaticStartCallback_, this, ros::TransportHints().tcpNoDelay());
Expand Down Expand Up @@ -914,7 +912,6 @@ void Acquisition::prefillUavStatus() {
uav_status_.mass_set = 0.0;
uav_status_.custom_topics.clear();
uav_status_.custom_string_outputs.clear();
uav_status_.custom_services.clear();
uav_status_.flying_normally = false;
uav_status_.null_tracker = true;
uav_status_.have_goal = false;
Expand Down Expand Up @@ -1535,24 +1532,6 @@ void Acquisition::constraintManagerCallback(const mrs_msgs::ConstraintManagerDia

//}

/* setServiceCallback() //{ */

void Acquisition::setServiceCallback(const std_msgs::String& msg) {

if (!initialized_) {
return;
}

{
std::scoped_lock lock(mutex_status_msg_);

if (std::find(uav_status_.custom_services.begin(), uav_status_.custom_services.end(), msg.data) == uav_status_.custom_services.end()) {
uav_status_.custom_services.push_back(msg.data);
}
}
}
//}

/* tfStaticCallback() //{ */

void Acquisition::tfStaticCallback(const tf2_msgs::TFMessage& msg) {
Expand Down
1 change: 0 additions & 1 deletion src/status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2846,7 +2846,6 @@ void Status::prefillUavStatus() {
uav_status_.mass_set = 0.0;
uav_status_.custom_topics.clear();
uav_status_.custom_string_outputs.clear();
uav_status_.custom_services.clear();
uav_status_.flying_normally = false;
uav_status_.null_tracker = true;
uav_status_.have_goal = false;
Expand Down

0 comments on commit 769d066

Please sign in to comment.