Gazebo Sim

API Reference

8.6.0
MulticopterVelocityControl.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 #ifndef GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_
18 #define GZ_SIM_SYSTEMS_MULTICOPTERVELOCITYCONTROL_HH_
19 
20 #include <Eigen/Geometry>
21 #include <memory>
22 #include <string>
23 
24 #include <gz/msgs/actuators.pb.h>
25 #include <gz/msgs/boolean.pb.h>
26 #include <gz/msgs/twist.pb.h>
27 #include <gz/transport/Node.hh>
28 
29 #include <gz/sim/System.hh>
30 #include "gz/sim/Link.hh"
31 #include "gz/sim/Model.hh"
32 
33 #include "Common.hh"
34 #include "LeeVelocityController.hh"
35 
36 namespace gz
37 {
38 namespace sim
39 {
40 // Inline bracket to help doxygen filtering.
41 inline namespace GZ_SIM_VERSION_NAMESPACE {
42 namespace systems
43 {
154  : public System,
155  public ISystemConfigure,
156  public ISystemPreUpdate
157  {
159  public: MulticopterVelocityControl() = default;
160 
161  // Documentation inherited
162  public: void Configure(const Entity &_entity,
165  EventManager &_eventMgr) override;
166 
167  // Documentation inherited
168  public: void PreUpdate(
169  const gz::sim::UpdateInfo &_info,
170  gz::sim::EntityComponentManager &_ecm) override;
171 
176  private: void OnTwist(const msgs::Twist &_msg);
177 
183  private: void OnEnable(const msgs::Boolean &_msg);
184 
188  private: void PublishRotorVelocities(
190  const Eigen::VectorXd &_vels);
191 
195  private: math::Inertiald VehicleInertial(
196  const EntityComponentManager &_ecm,
197  Entity _entity);
198 
200  private: Model model{kNullEntity};
201 
203  private: std::string comLinkName;
204 
206  private: Entity comLinkEntity;
207 
209  private: std::string robotNamespace;
210 
212  private: std::string commandSubTopic{"cmd_vel"};
213 
215  private: std::string enableSubTopic{"enable"};
216 
218  private: transport::Node node;
219 
222  private: Eigen::VectorXd rotorVelocities;
223 
226  velocityController;
227 
229  private: multicopter_control::NoiseParameters noiseParameters;
230 
234  private: std::optional<msgs::Twist> cmdVelMsg;
235 
237  private: math::Vector3d maximumLinearVelocity;
238 
240  private: math::Vector3d maximumAngularVelocity;
241 
243  private: std::mutex cmdVelMsgMutex;
244 
247  private: msgs::Actuators rotorVelocitiesMsg;
248 
250  private: bool initialized{false};
251 
253  private: std::atomic<bool> controllerActive{true};
254  };
255  }
256 }
257 }
258 }
259 
260 #endif