32 #pragma GCC diagnostic ignored "-Wwrite-strings"    38 #include <eigen3/Eigen/Core>    51   firmware_(board_, comm_)
    67     ROS_FATAL(
"A ROS node for Gazebo has not been initialized, unable to load plugin");
    70   ROS_INFO(
"Loaded the ROSflight SIL plugin");
    80   if (_sdf->HasElement(
"namespace"))
    81     namespace_ = _sdf->GetElement(
"namespace")->Get<std::string>();
    83     gzerr << 
"[ROSflight_SIL] Please specify a namespace.\n";
    86   gzmsg << 
"loading parameters from " << 
namespace_ << 
" ns\n";
    88   if (_sdf->HasElement(
"linkName"))
    89     link_name_ = _sdf->GetElement(
"linkName")->Get<std::string>();
    91     gzerr << 
"[ROSflight_SIL] Please specify a linkName of the forces and moments plugin.\n";
    94     gzthrow(
"[ROSflight_SIL] Couldn't find specified link \"" << 
link_name_ << 
"\".");
    97   if (_sdf->HasElement(
"mavType")) {
    98     mav_type_ = _sdf->GetElement(
"mavType")->Get<std::string>();
   102     gzerr << 
"[rosflight_sim] Please specify a value for parameter \"mavType\".\n";
   110     gzthrow(
"unknown or unsupported mav type\n");
   132   Eigen::Matrix3d NWU_to_NED;
   133   NWU_to_NED << 1, 0, 0, 0, -1, 0, 0, 0, -1;
   145   state.
t = _info.simTime.Double();
   152   link_->AddRelativeForce(force);
   153   link_->AddRelativeTorque(torque);
   162     link_->ResetPhysicsStates();
   169   Eigen::Vector3d wind;
   170   wind << msg.x, msg.y, msg.z;
   181   nav_msgs::Odometry truth;
   202   truth.pose.pose.orientation.y *= -1.0;
   203   truth.pose.pose.orientation.z *= -1.0;
   204   truth.pose.pose.position.y *= -1.0;
   205   truth.pose.pose.position.z *= -1.0;
   206   truth.twist.twist.linear.y *= -1.0;
   207   truth.twist.twist.linear.z *= -1.0;
   208   truth.twist.twist.angular.y *= -1.0;
   209   truth.twist.twist.angular.z *= -1.0;
   229   return eig_quat.toRotationMatrix();
 GZ_REGISTER_MODEL_PLUGIN(GazeboRosElevator)
ros::Publisher truth_NWU_pub_
#define GZ_COMPAT_GET_Z(VECTOR)
void publish(const boost::shared_ptr< M > &message) const 
gazebo::math::Vector3 GazeboVector
virtual void set_wind(Eigen::Vector3d wind)=0
ROSCPP_DECL bool isInitialized()
const int * get_outputs() const 
#define GZ_COMPAT_GET_X(VECTOR)
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)
void gazebo_setup(gazebo::physics::LinkPtr link, gazebo::physics::WorldPtr world, gazebo::physics::ModelPtr model, ros::NodeHandle *nh, std::string mav_type)
Eigen::Matrix< double, 6, 1 > forces_
#define GZ_COMPAT_GET_WORLD_COG_POSE(LINK_PTR)
MAVForcesAndMoments * mav_dynamics_
GazeboVector vec3_to_gazebo_from_eigen(Eigen::Vector3d vec)
gazebo::math::Pose GazeboPose
#define GZ_COMPAT_GET_W(VECTOR)
#define GZ_COMPAT_GET_ROT(POSE)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
rosflight_firmware::ROSflight firmware_
gazebo::physics::WorldPtr world_
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_
#define GZ_COMPAT_DISCONNECT_WORLD_UPDATE_BEGIN(CONNECTION)
#define GZ_COMPAT_GET_POS(POSE)
ros::Publisher truth_NED_pub_
gazebo::physics::LinkPtr link_
void windCallback(const geometry_msgs::Vector3 &msg)
#define GZ_COMPAT_GET_SIM_TIME(WORLD_PTR)
#define GZ_COMPAT_GET_Y(VECTOR)
#define GZ_COMPAT_GET_RELATIVE_LINEAR_VEL(LINK_PTR)
gazebo::physics::ModelPtr model_
gazebo::math::Quaternion GazeboQuaternion