rosflight_sil.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #pragma GCC diagnostic ignored "-Wwrite-strings"
33 
34 #include <cstdint>
35 #include <cstdio>
36 #include <sstream>
37 
38 #include <eigen3/Eigen/Core>
39 
42 
43 namespace rosflight_sim
44 {
45 ROSflightSIL::ROSflightSIL() : gazebo::ModelPlugin(), nh_(nullptr), comm_(board_), firmware_(board_, comm_) {}
46 
48 {
50  if (nh_)
51  {
52  nh_->shutdown();
53  delete nh_;
54  }
55 }
56 
57 void ROSflightSIL::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf)
58 {
59  if (!ros::isInitialized())
60  {
61  ROS_FATAL("A ROS node for Gazebo has not been initialized, unable to load plugin");
62  return;
63  }
64  ROS_INFO("Loaded the ROSflight SIL plugin");
65 
66  model_ = _model;
67  world_ = model_->GetWorld();
68 
69  namespace_.clear();
70 
71  /*
72  * Connect the Plugin to the Robot and Save pointers to the various elements in the simulation
73  */
74  if (_sdf->HasElement("namespace"))
75  namespace_ = _sdf->GetElement("namespace")->Get<std::string>();
76  else
77  gzerr << "[ROSflight_SIL] Please specify a namespace.\n";
79 
80  gzmsg << "loading parameters from " << namespace_ << " ns\n";
81 
82  if (_sdf->HasElement("linkName"))
83  link_name_ = _sdf->GetElement("linkName")->Get<std::string>();
84  else
85  gzerr << "[ROSflight_SIL] Please specify a linkName of the forces and moments plugin.\n";
86  link_ = model_->GetLink(link_name_);
87  if (link_ == NULL)
88  gzthrow("[ROSflight_SIL] Couldn't find specified link \"" << link_name_ << "\".");
89 
90  /* Load Params from Gazebo Server */
91  if (_sdf->HasElement("mavType"))
92  {
93  mav_type_ = _sdf->GetElement("mavType")->Get<std::string>();
94  }
95  else
96  {
97  mav_type_ = "multirotor";
98  gzerr << "[rosflight_sim] Please specify a value for parameter \"mavType\".\n";
99  }
100 
101  if (mav_type_ == "multirotor")
103  else if (mav_type_ == "fixedwing")
104  mav_dynamics_ = new Fixedwing(nh_);
105  else
106  gzthrow("unknown or unsupported mav type\n");
107 
108  // Initialize the Firmware
110  firmware_.init();
111 
112  // Connect the update function to the simulation
113  updateConnection_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&ROSflightSIL::OnUpdate, this, _1));
114 
116 
117  truth_NED_pub_ = nh_->advertise<nav_msgs::Odometry>("truth/NED", 1);
118  truth_NWU_pub_ = nh_->advertise<nav_msgs::Odometry>("truth/NWU", 1);
119 }
120 
121 // This gets called by the world update event.
122 void ROSflightSIL::OnUpdate(const gazebo::common::UpdateInfo& _info)
123 {
124  // We run twice so that that functions that take place when we don't have new IMU data get run
125  firmware_.run();
126  firmware_.run();
127 
128  Eigen::Matrix3d NWU_to_NED;
129  NWU_to_NED << 1, 0, 0, 0, -1, 0, 0, 0, -1;
130 
135 
136  // Convert gazebo types to Eigen and switch to NED frame
137  state.pos = NWU_to_NED * vec3_to_eigen_from_gazebo(GZ_COMPAT_GET_POS(pose));
138  state.rot = NWU_to_NED * rotation_to_eigen_from_gazebo(GZ_COMPAT_GET_ROT(pose));
139  state.vel = NWU_to_NED * vec3_to_eigen_from_gazebo(vel);
140  state.omega = NWU_to_NED * vec3_to_eigen_from_gazebo(omega);
141  state.t = _info.simTime.Double();
142 
144 
145  // apply the forces and torques to the joint (apply in NWU)
146  GazeboVector force = vec3_to_gazebo_from_eigen(NWU_to_NED * forces_.block<3, 1>(0, 0));
147  GazeboVector torque = vec3_to_gazebo_from_eigen(NWU_to_NED * forces_.block<3, 1>(3, 0));
148  link_->AddRelativeForce(force);
149  link_->AddRelativeTorque(torque);
150 
151  publishTruth();
152 }
153 
155 {
156  link_->SetWorldPose(initial_pose_);
157  link_->ResetPhysicsStates();
158  // start_time_us_ = (uint64_t)(world_->GetSimTime().Double() * 1e3);
159  // rosflight_init();
160 }
161 
162 void ROSflightSIL::windCallback(const geometry_msgs::Vector3& msg)
163 {
164  Eigen::Vector3d wind;
165  wind << msg.x, msg.y, msg.z;
166  mav_dynamics_->set_wind(wind);
167 }
168 
170 {
174 
175  // Publish truth
176  nav_msgs::Odometry truth;
177  truth.header.stamp.sec = GZ_COMPAT_GET_SIM_TIME(world_).sec;
178  truth.header.stamp.nsec = GZ_COMPAT_GET_SIM_TIME(world_).nsec;
179  truth.header.frame_id = link_name_ + "_NWU";
180  truth.pose.pose.orientation.w = GZ_COMPAT_GET_W(GZ_COMPAT_GET_ROT(pose));
181  truth.pose.pose.orientation.x = GZ_COMPAT_GET_X(GZ_COMPAT_GET_ROT(pose));
182  truth.pose.pose.orientation.y = GZ_COMPAT_GET_Y(GZ_COMPAT_GET_ROT(pose));
183  truth.pose.pose.orientation.z = GZ_COMPAT_GET_Z(GZ_COMPAT_GET_ROT(pose));
184  truth.pose.pose.position.x = GZ_COMPAT_GET_X(GZ_COMPAT_GET_POS(pose));
185  truth.pose.pose.position.y = GZ_COMPAT_GET_Y(GZ_COMPAT_GET_POS(pose));
186  truth.pose.pose.position.z = GZ_COMPAT_GET_Z(GZ_COMPAT_GET_POS(pose));
187  truth.twist.twist.linear.x = GZ_COMPAT_GET_X(vel);
188  truth.twist.twist.linear.y = GZ_COMPAT_GET_Y(vel);
189  truth.twist.twist.linear.z = GZ_COMPAT_GET_Z(vel);
190  truth.twist.twist.angular.x = GZ_COMPAT_GET_X(omega);
191  truth.twist.twist.angular.y = GZ_COMPAT_GET_Y(omega);
192  truth.twist.twist.angular.z = GZ_COMPAT_GET_Z(omega);
193  truth_NWU_pub_.publish(truth);
194 
195  // Convert to NED
196  truth.header.frame_id = link_name_ + "_NED";
197  truth.pose.pose.orientation.y *= -1.0;
198  truth.pose.pose.orientation.z *= -1.0;
199  truth.pose.pose.position.y *= -1.0;
200  truth.pose.pose.position.z *= -1.0;
201  truth.twist.twist.linear.y *= -1.0;
202  truth.twist.twist.linear.z *= -1.0;
203  truth.twist.twist.angular.y *= -1.0;
204  truth.twist.twist.angular.z *= -1.0;
205  truth_NED_pub_.publish(truth);
206 }
207 
209 {
210  Eigen::Vector3d out;
211  out << GZ_COMPAT_GET_X(vec), GZ_COMPAT_GET_Y(vec), GZ_COMPAT_GET_Z(vec);
212  return out;
213 }
214 
216 {
217  GazeboVector out(vec(0), vec(1), vec(2));
218  return out;
219 }
220 
222 {
223  Eigen::Quaterniond eig_quat(GZ_COMPAT_GET_W(quat), GZ_COMPAT_GET_X(quat), GZ_COMPAT_GET_Y(quat),
224  GZ_COMPAT_GET_Z(quat));
225  return eig_quat.toRotationMatrix();
226 }
227 
229 } // namespace rosflight_sim
GZ_REGISTER_MODEL_PLUGIN(GazeboRosElevator)
#define ROS_FATAL(...)
ros::Publisher truth_NWU_pub_
Definition: rosflight_sil.h:87
#define GZ_COMPAT_GET_Z(VECTOR)
Definition: gz_compat.h:78
void publish(const boost::shared_ptr< M > &message) const
gazebo::math::Vector3 GazeboVector
Definition: gz_compat.h:72
virtual void set_wind(Eigen::Vector3d wind)=0
ROSCPP_DECL bool isInitialized()
const int * get_outputs() const
Definition: sil_board.h:223
#define GZ_COMPAT_GET_X(VECTOR)
Definition: gz_compat.h:76
Eigen::Matrix3d rotation_to_eigen_from_gazebo(GazeboQuaternion vec)
Eigen::Vector3d vec3_to_eigen_from_gazebo(GazeboVector vec)
#define GZ_COMPAT_GET_RELATIVE_ANGULAR_VEL(LINK_PTR)
Definition: gz_compat.h:90
void gazebo_setup(gazebo::physics::LinkPtr link, gazebo::physics::WorldPtr world, gazebo::physics::ModelPtr model, ros::NodeHandle *nh, std::string mav_type)
Definition: sil_board.cpp:56
Eigen::Matrix< double, 6, 1 > forces_
Definition: rosflight_sil.h:92
#define GZ_COMPAT_GET_WORLD_COG_POSE(LINK_PTR)
Definition: gz_compat.h:91
MAVForcesAndMoments * mav_dynamics_
Definition: rosflight_sil.h:89
GazeboVector vec3_to_gazebo_from_eigen(Eigen::Vector3d vec)
gazebo::math::Pose GazeboPose
Definition: gz_compat.h:73
#define ROS_INFO(...)
#define GZ_COMPAT_GET_W(VECTOR)
Definition: gz_compat.h:79
#define GZ_COMPAT_GET_ROT(POSE)
Definition: gz_compat.h:85
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t out
rosflight_firmware::ROSflight firmware_
Definition: rosflight_sil.h:72
gazebo::physics::WorldPtr world_
Definition: rosflight_sil.h:78
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override
virtual Eigen::Matrix< double, 6, 1 > updateForcesAndTorques(Current_State x, const int act_cmds[])=0
void OnUpdate(const gazebo::common::UpdateInfo &_info)
gazebo::event::ConnectionPtr updateConnection_
Definition: rosflight_sil.h:83
#define GZ_COMPAT_DISCONNECT_WORLD_UPDATE_BEGIN(CONNECTION)
Definition: gz_compat.h:97
#define NULL
#define GZ_COMPAT_GET_POS(POSE)
Definition: gz_compat.h:84
ros::Publisher truth_NED_pub_
Definition: rosflight_sil.h:86
gazebo::physics::LinkPtr link_
Definition: rosflight_sil.h:80
void windCallback(const geometry_msgs::Vector3 &msg)
#define GZ_COMPAT_GET_SIM_TIME(WORLD_PTR)
Definition: gz_compat.h:87
#define GZ_COMPAT_GET_Y(VECTOR)
Definition: gz_compat.h:77
#define GZ_COMPAT_GET_RELATIVE_LINEAR_VEL(LINK_PTR)
Definition: gz_compat.h:88
gazebo::physics::ModelPtr model_
Definition: rosflight_sil.h:79
gazebo::math::Quaternion GazeboQuaternion
Definition: gz_compat.h:74


rosflight_sim
Author(s): James Jackson, Gary Ellingson, Daniel Koch
autogenerated on Thu Apr 15 2021 05:09:58