Skip to content

Commit

Permalink
Enable inherited model topic name. (#1689)
Browse files Browse the repository at this point in the history
Allows for inheriting model name for robotNamespace when SDF element is not set and provides a debug message showing the topics it subscribes to.

Signed-off-by: Benjamin Perseghetti <[email protected]>
Co-authored-by: Nate Koenig <[email protected]>
  • Loading branch information
bperseghetti and nkoenig authored Sep 22, 2022
1 parent 721bc35 commit 6b48eea
Showing 1 changed file with 8 additions and 1 deletion.
9 changes: 8 additions & 1 deletion src/systems/multicopter_motor_model/MulticopterMotorModel.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
* Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
* Copyright 2016 Geoffrey Hunter <[email protected]>
* Copyright (C) 2019 Open Source Robotics Foundation
* Copyright (C) 2022 Benjamin Perseghetti, Rudis Laboratories
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -49,6 +50,7 @@
#include "ignition/gazebo/components/Wind.hh"
#include "ignition/gazebo/Link.hh"
#include "ignition/gazebo/Model.hh"
#include "ignition/gazebo/Util.hh"

// from rotors_gazebo_plugins/include/rotors_gazebo_plugins/common.h
/// \brief This class can be used to apply a first order filter on a signal.
Expand Down Expand Up @@ -250,7 +252,8 @@ void MulticopterMotorModel::Configure(const Entity &_entity,
}
else
{
ignerr << "Please specify a robotNamespace.\n";
ignwarn << "No robotNamespace set using entity name.\n";
this->dataPtr->robotNamespace = this->dataPtr->model.Name(_ecm);
}

// Get params from SDF
Expand Down Expand Up @@ -365,6 +368,10 @@ void MulticopterMotorModel::Configure(const Entity &_entity,
<< "]" << std::endl;
return;
}
else
{
igndbg << "Listening to topic: " << topic << std::endl;
}
this->dataPtr->node.Subscribe(topic,
&MulticopterMotorModelPrivate::OnActuatorMsg, this->dataPtr.get());
}
Expand Down

0 comments on commit 6b48eea

Please sign in to comment.