Gazebo Sim

API Reference

7.9.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 {
112 
153  : public System,
154  public ISystemConfigure,
155  public ISystemPreUpdate
156  {
158  public: MulticopterVelocityControl() = default;
159 
160  // Documentation inherited
161  public: void Configure(const Entity &_entity,
164  EventManager &_eventMgr) override;
165 
166  // Documentation inherited
167  public: void PreUpdate(
168  const gz::sim::UpdateInfo &_info,
169  gz::sim::EntityComponentManager &_ecm) override;
170 
175  private: void OnTwist(const msgs::Twist &_msg);
176 
182  private: void OnEnable(const msgs::Boolean &_msg);
183 
187  private: void PublishRotorVelocities(
189  const Eigen::VectorXd &_vels);
190 
194  private: math::Inertiald VehicleInertial(
195  const EntityComponentManager &_ecm,
196  Entity _entity);
197 
199  private: Model model{kNullEntity};
200 
202  private: std::string comLinkName;
203 
205  private: Entity comLinkEntity;
206 
208  private: std::string robotNamespace;
209 
211  private: std::string commandSubTopic{"cmd_vel"};
212 
214  private: std::string enableSubTopic{"enable"};
215 
217  private: transport::Node node;
218 
221  private: Eigen::VectorXd rotorVelocities;
222 
225  velocityController;
226 
228  private: multicopter_control::NoiseParameters noiseParameters;
229 
233  private: std::optional<msgs::Twist> cmdVelMsg;
234 
236  private: math::Vector3d maximumLinearVelocity;
237 
239  private: math::Vector3d maximumAngularVelocity;
240 
242  private: std::mutex cmdVelMsgMutex;
243 
246  private: msgs::Actuators rotorVelocitiesMsg;
247 
249  private: bool initialized{false};
250 
252  private: std::atomic<bool> controllerActive{true};
253  };
254  }
255 }
256 }
257 }
258 
259 #endif